Add Doxygen documentation into the code

This commit is contained in:
Daniel Chappuis 2013-03-05 23:09:50 +01:00
parent 03cddcf568
commit 04a31c696c
52 changed files with 1529 additions and 1413 deletions

View File

@ -31,56 +31,53 @@
#include <cassert>
#include "../configuration.h"
// Namespace reactphysics3d
/// Namespace reactphysics3d
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class Body :
This class is an abstract class to represent a body of the physics
engine.
-------------------------------------------------------------------
*/
// Class Body
/**
* This class is an abstract class to represent a body of the physics engine.
*/
class Body {
protected :
// -------------------- Attributes -------------------- //
// ID of the body
/// ID of the body
bodyindex mID;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
Body(const Body& body);
// Private assignment operator
/// Private assignment operator
Body& operator=(const Body& body);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
Body(bodyindex id);
// Destructor
/// Destructor
virtual ~Body();
// Return the id of the body
/// Return the id of the body
bodyindex getID() const;
// Smaller than operator
/// Smaller than operator
bool operator<(const Body& body2) const;
// Larger than operator
/// Larger than operator
bool operator>(const Body& body2) const;
// Equal operator
/// Equal operator
bool operator==(const Body& body2) const;
// Not equal operator
/// Not equal operator
bool operator!=(const Body& body2) const;
};

View File

@ -35,116 +35,114 @@
#include "../collision/shapes/CollisionShape.h"
#include "../configuration.h"
// Namespace reactphysics3d
/// Namespace reactphysics3d
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class CollisionBody :
This class represents a body that is able to collide with others
bodies. This class inherits from the Body class.
-------------------------------------------------------------------
*/
// Class CollisionBody
/**
* This class represents a body that is able to collide with others
* bodies. This class inherits from the Body class.
*/
class CollisionBody : public Body {
protected :
// -------------------- Attributes -------------------- //
// Collision shape of the body
/// Collision shape of the body
CollisionShape* mCollisionShape;
// Position and orientation of the body
/// Position and orientation of the body
Transform mTransform;
// Last position and orientation of the body
/// Last position and orientation of the body
Transform mOldTransform;
// Interpolation factor used for the state interpolation
/// Interpolation factor used for the state interpolation
decimal mInterpolationFactor;
// True if the body is active (not sleeping)
/// True if the body is active (not sleeping)
bool mIsActive;
// True if the body is able to move
/// True if the body is able to move
bool mIsMotionEnabled;
// True if the body can collide with others bodies
/// True if the body can collide with others bodies
bool mIsCollisionEnabled;
// AABB for Broad-Phase collision detection
/// AABB for Broad-Phase collision detection
AABB* mAabb;
// True if the body has moved during the last frame
/// True if the body has moved during the last frame
bool mHasMoved;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
CollisionBody(const CollisionBody& body);
// Private assignment operator
/// Private assignment operator
CollisionBody& operator=(const CollisionBody& body);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
CollisionBody(const Transform& transform, CollisionShape* collisionShape, bodyindex id);
// Destructor
/// Destructor
virtual ~CollisionBody();
// Return true if the body has moved during the last frame
/// Return true if the body has moved during the last frame
bool getHasMoved() const;
// Set the hasMoved variable (true if the body has moved during the last frame)
/// Set the hasMoved variable (true if the body has moved during the last frame)
void setHasMoved(bool hasMoved);
// Return the collision shape
/// Return the collision shape
CollisionShape* getCollisionShape() const;
// Set the collision shape
/// Set the collision shape
void setCollisionShape(CollisionShape* collisionShape);
// Return true for an active body
/// Return true for an active body
bool getIsActive() const;
// Set the isActive variable
/// Set the isActive variable
void setIsActive(bool isActive);
// Return the current position and orientation
/// Return the current position and orientation
const Transform& getTransform() const;
// Set the current position and orientation
/// Set the current position and orientation
void setTransform(const Transform& transform);
// Return the AAABB of the body
/// Return the AAABB of the body
const AABB* getAABB() const;
// Return the interpolated transform for rendering
/// Return the interpolated transform for rendering
Transform getInterpolatedTransform() const;
// Set the interpolation factor of the body
/// Set the interpolation factor of the body
void setInterpolationFactor(decimal factor);
// Return if the rigid body can move
/// Return if the rigid body can move
bool getIsMotionEnabled() const;
// Set the value to true if the body can move
/// Set the value to true if the body can move
void setIsMotionEnabled(bool isMotionEnabled);
// Return true if the body can collide with others bodies
/// Return true if the body can collide with others bodies
bool getIsCollisionEnabled() const;
// Set the isCollisionEnabled value
/// Set the isCollisionEnabled value
void setIsCollisionEnabled(bool isCollisionEnabled);
// Update the old transform with the current one
/// Update the old transform with the current one.
void updateOldTransform();
// Update the Axis-Aligned Bounding Box coordinates
/// Update the Axis-Aligned Bounding Box coordinates
void updateAABB();
};
@ -232,8 +230,8 @@ inline void CollisionBody::setIsCollisionEnabled(bool isCollisionEnabled) {
mIsCollisionEnabled = isCollisionEnabled;
}
// Update the old transform with the current one
// This is used to compute the interpolated position and orientation of the body
// Update the old transform with the current one.
/// This is used to compute the interpolated position and orientation of the body
inline void CollisionBody::updateOldTransform() {
mOldTransform = mTransform;
}

View File

@ -31,17 +31,16 @@
#include "CollisionBody.h"
#include "../mathematics/mathematics.h"
// Namespace reactphysics3d
/// Namespace reactphysics3d
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class RigidBody :
This class represents a rigid body of the physics
engine. A rigid body is a non-deformable body that
has a constant mass. This class inherits from the
CollisionBody class.
-------------------------------------------------------------------
*/
// Class RigidBody
/**
* This class represents a rigid body of the physics
* engine. A rigid body is a non-deformable body that
* has a constant mass. This class inherits from the
* CollisionBody class.
*/
class RigidBody : public CollisionBody {
protected :
@ -50,123 +49,123 @@ class RigidBody : public CollisionBody {
// -------------------- Attributes -------------------- //
// Mass of the body
/// Mass of the body
decimal mMass;
// Linear velocity of the body
/// Linear velocity of the body
Vector3 mLinearVelocity;
// Angular velocity of the body
/// Angular velocity of the body
Vector3 mAngularVelocity;
// Current external force on the body
/// Current external force on the body
Vector3 mExternalForce;
// Current external torque on the body
/// Current external torque on the body
Vector3 mExternalTorque;
// Local inertia tensor of the body (in local-space)
/// Local inertia tensor of the body (in local-space)
Matrix3x3 mInertiaTensorLocal;
// Inverse of the inertia tensor of the body
/// Inverse of the inertia tensor of the body
Matrix3x3 mInertiaTensorLocalInverse;
// Inverse of the mass of the body
/// Inverse of the mass of the body
decimal mMassInverse;
// Coefficient of restitution (between 0 and 1) where 1 is for a very bouncy body
/// Coefficient of restitution (between 0 and 1) where 1 is for a very bouncy body
decimal mRestitution;
// Friction coefficient
/// Friction coefficient
decimal mFrictionCoefficient;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
RigidBody(const RigidBody& body);
// Private assignment operator
/// Private assignment operator
RigidBody& operator=(const RigidBody& body);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
RigidBody(const Transform& transform, decimal mass, const Matrix3x3& inertiaTensorLocal,
CollisionShape* collisionShape, bodyindex id);
// Destructor
/// Destructor
virtual ~RigidBody();
// Return the mass of the body
/// Return the mass of the body
decimal getMass() const;
// Set the mass of the body
/// Set the mass of the body
void setMass(decimal mass);
// Return the linear velocity
/// Return the linear velocity
Vector3 getLinearVelocity() const;
// Set the linear velocity of the body
/// Set the linear velocity of the body
void setLinearVelocity(const Vector3& linearVelocity);
// Return the angular velocity
/// Return the angular velocity
Vector3 getAngularVelocity() const;
// Set the angular velocity
/// Set the angular velocity
void setAngularVelocity(const Vector3& angularVelocity);
// Set the inverse of the mass
/// Set the inverse of the mass
void setMassInverse(decimal massInverse);
// Return the current external force of the body
/// Return the current external force of the body
Vector3 getExternalForce() const;
// Set the current external force on the body
/// Set the current external force on the body
void setExternalForce(const Vector3& force);
// Return the current external torque of the body
/// Return the current external torque of the body
Vector3 getExternalTorque() const;
// Set the current external torque of the body
/// Set the current external torque of the body
void setExternalTorque(const Vector3& torque);
// Return the inverse of the mass of the body
/// Return the inverse of the mass of the body
decimal getMassInverse() const;
// Return the local inertia tensor of the body (in body coordinates)
/// Return the local inertia tensor of the body (in body coordinates)
Matrix3x3 getInertiaTensorLocal() const;
// Set the local inertia tensor of the body (in body coordinates)
/// Set the local inertia tensor of the body (in body coordinates)
void setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal);
// Get the inverse of the inertia tensor
/// Get the inverse of the inertia tensor
Matrix3x3 getInertiaTensorLocalInverse() const;
// Return the inertia tensor in world coordinates
/// Return the inertia tensor in world coordinates.
Matrix3x3 getInertiaTensorWorld() const;
// Return the inverse of the inertia tensor in world coordinates
/// Return the inverse of the inertia tensor in world coordinates.
Matrix3x3 getInertiaTensorInverseWorld() const;
// Get the restitution coefficient
/// Get the restitution coefficient
decimal getRestitution() const;
// Set the restitution coefficient
/// Set the restitution coefficient
void setRestitution(decimal restitution) throw(std::invalid_argument);
// Get the friction coefficient
/// Get the friction coefficient
decimal getFrictionCoefficient() const;
// Set the friction coefficient
/// Set the friction coefficient
void setFrictionCoefficient(decimal frictionCoefficient);
};
// Method that return the mass of the body
inline decimal RigidBody::getMass() const {
return mMass;
};
}
// Method that set the mass of the body
inline void RigidBody::setMass(decimal mass) {
@ -232,12 +231,12 @@ inline void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal
mInertiaTensorLocal = inertiaTensorLocal;
}
// Return the inertia tensor in world coordinates
// The inertia tensor I_w in world coordinates is computed
// with the local inertia tensor I_b in body coordinates
// by I_w = R * I_b * R^T
// where R is the rotation matrix (and R^T its transpose) of
// the current orientation quaternion of the body
// Return the inertia tensor in world coordinates.
/// The inertia tensor I_w in world coordinates is computed
/// with the local inertia tensor I_b in body coordinates
/// by I_w = R * I_b * R^T
/// where R is the rotation matrix (and R^T its transpose) of
/// the current orientation quaternion of the body
inline Matrix3x3 RigidBody::getInertiaTensorWorld() const {
// Compute and return the inertia tensor in world coordinates
@ -245,12 +244,12 @@ inline Matrix3x3 RigidBody::getInertiaTensorWorld() const {
mTransform.getOrientation().getMatrix().getTranspose();
}
// Return the inverse of the inertia tensor in world coordinates
// The inertia tensor I_w in world coordinates is computed with the
// local inverse inertia tensor I_b^-1 in body coordinates
// by I_w = R * I_b^-1 * R^T
// where R is the rotation matrix (and R^T its transpose) of the
// current orientation quaternion of the body
// Return the inverse of the inertia tensor in world coordinates.
/// The inertia tensor I_w in world coordinates is computed with the
/// local inverse inertia tensor I_b^-1 in body coordinates
/// by I_w = R * I_b^-1 * R^T
/// where R is the rotation matrix (and R^T its transpose) of the
/// current orientation quaternion of the body
inline Matrix3x3 RigidBody::getInertiaTensorInverseWorld() const {
// Compute and return the inertia tensor in world coordinates

View File

@ -29,48 +29,50 @@
// Libraries
#include "../body/CollisionBody.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// struct BroadPhasePair
// This structure represents a pair of bodies
// during the broad-phase collision detection
// Structure BroadPhasePair
/**
* This structure represents a pair of bodies
* during the broad-phase collision detection.
*/
struct BroadPhasePair {
public:
// -------------------- Attributes -------------------- //
// Pointer to the first body
/// Pointer to the first body
CollisionBody* body1;
// Pointer to the second body
/// Pointer to the second body
CollisionBody* body2;
// Previous cached separating axis
/// Previous cached separating axis
Vector3 previousSeparatingAxis;
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
BroadPhasePair(CollisionBody* body1, CollisionBody* body2);
// Destructor
/// Destructor
~BroadPhasePair();
// Return the pair of bodies index
/// Return the pair of bodies index
bodyindexpair getBodiesIndexPair() const;
// Smaller than operator
/// Smaller than operator
bool operator<(const BroadPhasePair& broadPhasePair2) const;
// Larger than operator
/// Larger than operator
bool operator>(const BroadPhasePair& broadPhasePair2) const;
// Equal operator
/// Equal operator
bool operator==(const BroadPhasePair& broadPhasePair2) const;
// Not equal operator
/// Not equal operator
bool operator!=(const BroadPhasePair& broadPhasePair2) const;
};

View File

@ -143,8 +143,8 @@ bool CollisionDetection::computeNarrowPhase() {
return collisionExists;
}
// Allow the broadphase to notify the collision detection about an overlapping pair
// This method is called by a broad-phase collision detection algorithm
// Allow the broadphase to notify the collision detection about an overlapping pair.
/// This method is called by a broad-phase collision detection algorithm
void CollisionDetection::broadPhaseNotifyAddedOverlappingPair(BodyPair* addedPair) {
// Get the pair of body index

View File

@ -41,63 +41,62 @@
#include <iostream> // TODO : Delete this
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Declarations
class BroadPhaseAlgorithm;
class CollisionWorld;
/* -------------------------------------------------------------------
Class CollisionDetection :
This class computes the collision detection algorithms. We first
perform a broad-phase algorithm to know which pairs of bodies can
collide and then we run a narrow-phase algorithm to compute the
collision contacts between bodies.
-------------------------------------------------------------------
*/
// Class CollisionDetection
/**
* This class computes the collision detection algorithms. We first
* perform a broad-phase algorithm to know which pairs of bodies can
* collide and then we run a narrow-phase algorithm to compute the
* collision contacts between bodies.
*/
class CollisionDetection {
private :
// -------------------- Attributes -------------------- //
// Pointer to the physics world
/// Pointer to the physics world
CollisionWorld* mWorld;
// Broad-phase overlapping pairs
/// Broad-phase overlapping pairs
std::map<bodyindexpair, BroadPhasePair*> mOverlappingPairs;
// Broad-phase algorithm
/// Broad-phase algorithm
BroadPhaseAlgorithm* mBroadPhaseAlgorithm;
// Narrow-phase GJK algorithm
/// Narrow-phase GJK algorithm
GJKAlgorithm mNarrowPhaseGJKAlgorithm;
// Narrow-phase Sphere vs Sphere algorithm
/// Narrow-phase Sphere vs Sphere algorithm
SphereVsSphereAlgorithm mNarrowPhaseSphereVsSphereAlgorithm;
// Memory pool for contactinfo
/// Memory pool for contactinfo
MemoryPool<ContactInfo> mMemoryPoolContactInfos;
// Memory pool for broad-phase pairs
/// Memory pool for broad-phase pairs
MemoryPool<BroadPhasePair> mMemoryPoolBroadPhasePairs;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
CollisionDetection(const CollisionDetection& collisionDetection);
// Private assignment operator
/// Private assignment operator
CollisionDetection& operator=(const CollisionDetection& collisionDetection);
// Compute the broad-phase collision detection
/// Compute the broad-phase collision detection
void computeBroadPhase();
// Compute the narrow-phase collision detection
/// Compute the narrow-phase collision detection
bool computeNarrowPhase();
// Select the narrow phase algorithm to use given two collision shapes
/// Select the narrow phase algorithm to use given two collision shapes
NarrowPhaseAlgorithm& SelectNarrowPhaseAlgorithm(CollisionShape* collisionShape1,
CollisionShape* collisionShape2);
@ -105,25 +104,25 @@ class CollisionDetection {
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
CollisionDetection(CollisionWorld* world);
// Destructor
/// Destructor
~CollisionDetection();
// Add a body to the collision detection
/// Add a body to the collision detection
void addBody(CollisionBody* body);
// Remove a body from the collision detection
/// Remove a body from the collision detection
void removeBody(CollisionBody* body);
// Compute the collision detection
/// Compute the collision detection
bool computeCollisionDetection();
// Allow the broadphase to notify the collision detection about a new overlapping pair
/// Allow the broadphase to notify the collision detection about a new overlapping pair.
void broadPhaseNotifyAddedOverlappingPair(BodyPair* pair);
// Allow the broadphase to notify the collision detection about a removed overlapping pair
/// Allow the broadphase to notify the collision detection about a removed overlapping pair
void broadPhaseNotifyRemovedOverlappingPair(BodyPair* pair);
};

View File

@ -33,45 +33,44 @@
// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Structure ContactInfo :
This structure contains informations about a collision contact
computed during the narrow-phase collision detection. Those
informations are use to compute the contact set for a contact
between two bodies.
-------------------------------------------------------------------
*/
// Structure ContactInfo
/**
* This structure contains informations about a collision contact
* computed during the narrow-phase collision detection. Those
* informations are used to compute the contact set for a contact
* between two bodies.
*/
struct ContactInfo {
private:
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
ContactInfo(const ContactInfo& contactInfo);
// Private assignment operator
/// Private assignment operator
ContactInfo& operator=(const ContactInfo& contactInfo);
public:
// -------------------- Attributes -------------------- //
// Normal vector the the collision contact in world space
/// Normal vector the the collision contact in world space
const Vector3 normal;
// Penetration depth of the contact
/// Penetration depth of the contact
const decimal penetrationDepth;
// Contact point of body 1 in local space of body 1
/// Contact point of body 1 in local space of body 1
const Vector3 localPoint1;
// Contact point of body 2 in local space of body 2
/// Contact point of body 2 in local space of body 2
const Vector3 localPoint2;
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
ContactInfo(const Vector3& normal, decimal penetrationDepth,
const Vector3& localPoint1, const Vector3& localPoint2);
};

View File

@ -31,68 +31,67 @@
#include "../../body/CollisionBody.h"
#include "PairManager.h"
// Namespace ReactPhysics3D
/// Namespace ReactPhysics3D
namespace reactphysics3d {
// Declarations
class CollisionDetection;
/* --------------------------------------------------------------------
Class BroadPhaseAlgorithm :
This class is an abstract class that represents an algorithm
used to perform the broad-phase of a collision detection. The
goal of the broad-phase algorithm is to compute the pair of bodies
that can collide. But it's important to understand that the
broad-phase doesn't compute only body pairs that can collide but
could also pairs of body that doesn't collide but are very close.
The goal of the broad-phase is to remove pairs of body that cannot
collide in order to avoid to much bodies to be tested in the
narrow-phase.
--------------------------------------------------------------------
*/
// Class BroadPhaseAlgorithm
/**
* This class is an abstract class that represents an algorithm
* used to perform the broad-phase of a collision detection. The
* goal of the broad-phase algorithm is to compute the pair of bodies
* that can collide. But it's important to understand that the
* broad-phase doesn't compute only body pairs that can collide but
* could also pairs of body that doesn't collide but are very close.
* The goal of the broad-phase is to remove pairs of body that cannot
* collide in order to avoid to much bodies to be tested in the
* narrow-phase.
*/
class BroadPhaseAlgorithm {
protected :
// -------------------- Attributes -------------------- //
// Pair manager containing the overlapping pairs
/// Pair manager containing the overlapping pairs
PairManager mPairManager;
// Reference to the collision detection object
/// Reference to the collision detection object
CollisionDetection& mCollisionDetection;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
BroadPhaseAlgorithm(const BroadPhaseAlgorithm& algorithm);
// Private assignment operator
/// Private assignment operator
BroadPhaseAlgorithm& operator=(const BroadPhaseAlgorithm& algorithm);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
BroadPhaseAlgorithm(CollisionDetection& collisionDetection);
// Destructor
/// Destructor
virtual ~BroadPhaseAlgorithm();
// Notify the broad-phase about a new object in the world
/// Notify the broad-phase about a new object in the world
virtual void addObject(CollisionBody* body, const AABB& aabb)=0;
// Notify the broad-phase about an object that has been removed from the world
/// Notify the broad-phase about an object that has been removed from the world
virtual void removeObject(CollisionBody* body)=0;
// Notify the broad-phase that the AABB of an object has changed
/// Notify the broad-phase that the AABB of an object has changed
virtual void updateObject(CollisionBody* body, const AABB& aabb)=0;
// Return a pointer to the first active pair (used to iterate over the active pairs)
/// Return a pointer to the first active pair (used to iterate over the active pairs)
BodyPair* beginOverlappingPairsPointer() const;
// Return a pointer to the last active pair (used to iterate over the active pairs)
/// Return a pointer to the last active pair (used to iterate over the active pairs)
BodyPair* endOverlappingPairsPointer() const;
};

View File

@ -32,50 +32,49 @@
#include <set>
#include <iostream>
// Namespace ReactPhysics3D
/// Namespace ReactPhysics3D
namespace reactphysics3d {
/* --------------------------------------------------------------------
Class NoBroadPhaseAlgorithm :
This class implements a broad-phase algorithm that does nothing.
It should be use if we don't want to perform a broad-phase for
the collision detection.
--------------------------------------------------------------------
*/
// Class NoBroadPhaseAlgorithm
/**
* This class implements a broad-phase algorithm that does nothing.
* It should be use if we don't want to perform a broad-phase for
* the collision detection.
*/
class NoBroadPhaseAlgorithm : public BroadPhaseAlgorithm {
protected :
// -------------------- Attributes -------------------- //
// All bodies of the world
/// All bodies of the world
std::set<CollisionBody*> mBodies;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
NoBroadPhaseAlgorithm(const NoBroadPhaseAlgorithm& algorithm);
// Private assignment operator
/// Private assignment operator
NoBroadPhaseAlgorithm& operator=(const NoBroadPhaseAlgorithm& algorithm);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
NoBroadPhaseAlgorithm(CollisionDetection& collisionDetection);
// Destructor
/// Destructor
virtual ~NoBroadPhaseAlgorithm();
// Notify the broad-phase about a new object in the world
/// Notify the broad-phase about a new object in the world
virtual void addObject(CollisionBody* body, const AABB& aabb);
// Notify the broad-phase about an object that has been removed from the world
/// Notify the broad-phase about an object that has been removed from the world
virtual void removeObject(CollisionBody* body);
// Notify the broad-phase that the AABB of an object has changed
/// Notify the broad-phase that the AABB of an object has changed
virtual void updateObject(CollisionBody* body, const AABB& aabb);
};

View File

@ -53,10 +53,10 @@ PairManager::~PairManager() {
free(mHashTable);
}
// Add a pair of bodies in the pair manager and returns a pointer to
// that pair. If the pair to add does not already exist in the set of
// overlapping pairs, it will be created and if it already exists, we only
// return a pointer to that pair.
// Add a pair of bodies in the pair manager and returns a pointer to that pair.
/// If the pair to add does not already exist in the set of
/// overlapping pairs, it will be created and if it already exists, we only
/// return a pointer to that pair.
BodyPair* PairManager::addPair(CollisionBody* body1, CollisionBody* body2) {
// Sort the bodies to have the body with smallest ID first
@ -109,8 +109,8 @@ BodyPair* PairManager::addPair(CollisionBody* body1, CollisionBody* body2) {
return newPair;
}
// Remove a pair of bodies from the pair manager. This method returns
// true if the pair has been found and removed.
// Remove a pair of bodies from the pair manager.
/// This method returns true if the pair has been found and removed.
bool PairManager::removePair(bodyindex id1, bodyindex id2) {
// Sort the bodies IDs

View File

@ -31,23 +31,28 @@
#include <utility>
// Namespace ReactPhysics3D
/// Namespace ReactPhysics3D
namespace reactphysics3d {
// Declaration
class CollisionDetection;
// struct BodyPair
// This structure represents a pair of bodies
// during the broad-phase collision detection
// Structure BodyPair
/**
* This structure represents a pair of bodies
* during the broad-phase collision detection.
*/
struct BodyPair {
public:
CollisionBody* body1; // Pointer to the first body
CollisionBody* body2; // Pointer to the second body
/// Pointer to the first body
CollisionBody* body1;
// Return the pair of bodies index
/// Pointer to the second body
CollisionBody* body2;
/// Return the pair of bodies index
bodyindexpair getBodiesIndexPair() const {
// Construct the pair of body index
@ -60,88 +65,87 @@ struct BodyPair {
}
};
/* --------------------------------------------------------------------
Class PairManager :
This class is a data-structure contains the pairs of bodies that
are overlapping during the broad-phase collision detection.
This class implements the pair manager described by Pierre Terdiman
in www.codercorner.com/SAP.pdf.
--------------------------------------------------------------------
*/
// Class PairManager
/**
* This class is a data-structure contains the pairs of bodies that
* are overlapping during the broad-phase collision detection.
* This class implements the pair manager described by Pierre Terdiman
* in www.codercorner.com/SAP.pdf.
*/
class PairManager {
private :
// -------------------- Attributes -------------------- //
// Number of elements in the hash table
/// Number of elements in the hash table
bodyindex mNbElementsHashTable;
// Hash mask for the hash function
/// Hash mask for the hash function
uint mHashMask;
// Number of overlapping pairs
/// Number of overlapping pairs
bodyindex mNbOverlappingPairs;
// Hash table that contains the offset of the first pair of the list of
// pairs with the same hash value in the "overlappingPairs" array
/// Hash table that contains the offset of the first pair of the list of
/// pairs with the same hash value in the "overlappingPairs" array
bodyindex* mHashTable;
// Array that contains for each offset, the offset of the next pair with
// the same hash value for a given same hash value
/// Array that contains for each offset, the offset of the next pair with
/// the same hash value for a given same hash value
bodyindex* mOffsetNextPair;
// Array that contains the overlapping pairs
/// Array that contains the overlapping pairs
BodyPair* mOverlappingPairs;
// Invalid ID
/// Invalid ID
static bodyindex INVALID_INDEX;
// Reference to the collision detection
/// Reference to the collision detection
CollisionDetection& mCollisionDetection;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
PairManager(const PairManager& pairManager);
// Private assignment operator
/// Private assignment operator
PairManager& operator=(const PairManager& pairManager);
// Sort the bodies according to their IDs (smallest ID first)
/// Sort the bodies according to their IDs (smallest ID first)
void sortBodiesUsingID(CollisionBody*& body1, CollisionBody*& body2) const;
// Sort the IDs (smallest ID first)
/// Sort the IDs (smallest ID first)
void sortIDs(bodyindex& id1, bodyindex& id2) const;
// Return true if pair1 and pair2 are the same
/// Return true if pair1 and pair2 are the same
bool isDifferentPair(const BodyPair& pair1, bodyindex pair2ID1, bodyindex pair2ID2) const;
// Compute the hash value of two bodies using their IDs
/// Compute the hash value of two bodies using their IDs
uint computeHashBodies(uint id1, uint id2) const;
// This method returns an hash value for a 32 bits key
/// This method returns an hash value for a 32 bits key.
int computeHash32Bits(int key) const;
// Return the next power of two
/// Return the next power of two
luint computeNextPowerOfTwo(luint number) const;
// Reallocate memory for more pairs
/// Reallocate memory for more pairs
void reallocatePairs();
// Shrink the allocated memory
/// Shrink the allocated memory
void shrinkMemory();
// Compute the offset of a given pair
/// Compute the offset of a given pair
bodyindex computePairOffset(const BodyPair* pair) const;
// Look for a pair in the set of overlapping pairs
/// Look for a pair in the set of overlapping pairs
BodyPair* lookForAPair(bodyindex id1, bodyindex id2, luint hashValue) const;
// Find a pair given two body IDs and an hash value
/// Find a pair given two body IDs and an hash value.
BodyPair* findPairWithHashValue(bodyindex id1, bodyindex id2, luint hashValue) const;
// Remove a pair from the set of active pair
/// Remove a pair from the set of active pair
void removePairWithHashValue(bodyindex id1, bodyindex id2, luint hashValue,
bodyindex indexPair);
@ -149,48 +153,48 @@ class PairManager {
// ----- Methods ----- //
// Constructor
/// Constructor
PairManager(CollisionDetection& collisionDetection);
// Destructor
/// Destructor
~PairManager();
// Return the number of active pairs
/// Return the number of active pairs
bodyindex getNbOverlappingPairs() const;
// Add a pair of bodies in the pair manager
/// Add a pair of bodies in the pair manager and returns a pointer to that pair.
BodyPair* addPair(CollisionBody* body1, CollisionBody* body2);
// Remove a pair of bodies from the pair manager
/// Remove a pair of bodies from the pair manager.
bool removePair(bodyindex id1, bodyindex id2);
// Find a pair given two body IDs
/// Find a pair given two body IDs
BodyPair* findPair(bodyindex id1, bodyindex id2) const;
// Return a pointer to the first overlapping pair (used to
// iterate over the active pairs)
/// Return a pointer to the first overlapping pair (used to
/// iterate over the active pairs).
BodyPair* beginOverlappingPairsPointer() const;
// Return a pointer to the last overlapping pair (used to
// iterate over the active pairs)
/// Return a pointer to the last overlapping pair (used to
/// iterate over the active pairs).
BodyPair* endOverlappingPairsPointer() const;
// Register a callback function (using a function pointer) that will be
// called when a new overlapping pair is added in the pair manager
/// Register a callback function (using a function pointer) that will be
/// called when a new overlapping pair is added in the pair manager.
void registerAddedOverlappingPairCallback(void (CollisionDetection::*callbackFunction)
(const BodyPair* addedActivePair));
// Unregister the callback function that will be called
// when a new active pair is added in the pair manager
/// Unregister the callback function that will be called
/// when a new active pair is added in the pair manager
void unregisterAddedOverlappingPairCallback();
// Register a callback function (using a function pointer)
// that will be called when an overlapping pair is removed from the pair manager
/// Register a callback function (using a function pointer)
/// that will be called when an overlapping pair is removed from the pair manager
void registerRemovedOverlappingPairCallback(void (CollisionDetection::*callbackFunction)
(const BodyPair* removedActivePair));
// Unregister a callback function that will be called
// when a active pair is removed from the pair manager
/// Unregister a callback function that will be called
/// when a active pair is removed from the pair manager
void unregisterRemovedOverlappingPairCallback();
};
@ -242,10 +246,10 @@ inline void PairManager::sortIDs(bodyindex &id1, bodyindex &id2) const {
}
}
// This method returns an hash value for a 32 bits key
// using Thomas Wang's hash technique.
// This hash function can be found at :
// http://www.concentric.net/~ttwang/tech/inthash.htm
// This method returns an hash value for a 32 bits key.
/// using Thomas Wang's hash technique.
/// This hash function can be found at :
/// http://www.concentric.net/~ttwang/tech/inthash.htm
inline int PairManager::computeHash32Bits(int key) const {
key += ~(key << 15);
key ^= (key >> 10);
@ -272,9 +276,9 @@ inline BodyPair* PairManager::findPair(bodyindex id1, bodyindex id2) const {
lookForAPair(id1, id2, hashValue);
}
// Find a pair given two body IDs and an hash value
// This internal version is used to avoid computing multiple times in the
// caller method
// Find a pair given two body IDs and an hash value.
/// This internal version is used to avoid computing multiple times in the
/// caller method
inline BodyPair* PairManager::findPairWithHashValue(bodyindex id1, bodyindex id2,
luint hashValue) const {

View File

@ -64,7 +64,7 @@ SweepAndPruneAlgorithm::~SweepAndPruneAlgorithm() {
}
// Notify the broad-phase about a new object in the world
// This method adds the AABB of the object ion to broad-phase
/// This method adds the AABB of the object ion to broad-phase
void SweepAndPruneAlgorithm::addObject(CollisionBody* body, const AABB& aabb) {
bodyindex boxIndex;

View File

@ -33,20 +33,28 @@
#include <vector>
// Namespace ReactPhysics3D
/// Namespace ReactPhysics3D
namespace reactphysics3d {
// EndPoint structure that represent an end-point of an AABB
// on one of the three x,y or z axis
// Structure EndPoint
/**
* EndPoint structure that represent an end-point of an AABB
* on one of the three x,y or z axis.
*/
struct EndPoint {
public:
bodyindex boxID; // ID of the AABB box corresponding to this end-point
bool isMin; // True if the end-point is a minimum end-point of a box
uint value; // Value (one dimension coordinate) of the end-point
/// ID of the AABB box corresponding to this end-point
bodyindex boxID;
/// True if the end-point is a minimum end-point of a box
bool isMin;
/// Value (one dimension coordinate) of the end-point
uint value;
// Set the values of the endpoint
/// Set the values of the endpoint
void setValues(bodyindex boxID, bool isMin, uint value) {
this->boxID = boxID;
this->isMin = isMin;
@ -54,85 +62,95 @@ struct EndPoint {
}
};
// Structure BoxAABB that represents an AABB in the
// Sweep-And-Prune algorithm
// Structure BoxAABB
/**
* This structure represents an AABB in the Sweep-And-Prune algorithm
*/
struct BoxAABB {
public:
bodyindex min[3]; // Index of the 3 minimum end-points of the AABB over the x,y,z axis
bodyindex max[3]; // Index of the 3 maximum end-points of the AABB over the x,y,z axis
CollisionBody* body; // Body that corresponds to the owner of the AABB
/// Index of the 3 minimum end-points of the AABB over the x,y,z axis
bodyindex min[3];
/// Index of the 3 maximum end-points of the AABB over the x,y,z axis
bodyindex max[3];
/// Body that corresponds to the owner of the AABB
CollisionBody* body;
};
// Structure AABBInt
// Axis-Aligned Bounding box with integer coordinates
/**
* Axis-Aligned Bounding box with integer coordinates.
*/
struct AABBInt {
public:
uint min[3]; // Minimum values on the three axis
uint max[3]; // Maximum values on the three axis
/// Minimum values on the three axis
uint min[3];
/// Maximum values on the three axis
uint max[3];
// Constructor
/// Constructor
AABBInt(const AABB& aabb);
};
/* --------------------------------------------------------------------
Class SweepAndPruneAlgorithm :
This class implements the Sweep-And-Prune (SAP) broad-phase
collision detection algorithm. This class implements an
array-based implementation of the algorithm from Pierre Terdiman
that is described here : www.codercorner.com/SAP.pdf.
--------------------------------------------------------------------
*/
// Class SweepAndPruneAlgorithm
/**
* This class implements the Sweep-And-Prune (SAP) broad-phase
* collision detection algorithm. This class implements an
* array-based implementation of the algorithm from Pierre Terdiman
* that is described here : www.codercorner.com/SAP.pdf.
*/
class SweepAndPruneAlgorithm : public BroadPhaseAlgorithm {
protected :
// -------------------- Attributes -------------------- //
// Invalid array index
/// Invalid array index
static bodyindex INVALID_INDEX;
// Array that contains all the AABB boxes of the broad-phase
/// Array that contains all the AABB boxes of the broad-phase
BoxAABB* mBoxes;
// Array of end-points on the three axis
/// Array of end-points on the three axis
EndPoint* mEndPoints[3];
// Number of AABB boxes in the broad-phase
/// Number of AABB boxes in the broad-phase
bodyindex mNbBoxes;
// Max number of boxes in the boxes array
/// Max number of boxes in the boxes array
bodyindex mNbMaxBoxes;
// Indices that are not used by any boxes
/// Indices that are not used by any boxes
std::vector<bodyindex> mFreeBoxIndices;
// Map a body pointer to a box index
/// Map a body pointer to a box index
std::map<CollisionBody*,bodyindex> mMapBodyToBoxIndex;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
SweepAndPruneAlgorithm(const SweepAndPruneAlgorithm& algorithm);
// Private assignment operator
/// Private assignment operator
SweepAndPruneAlgorithm& operator=(const SweepAndPruneAlgorithm& algorithm);
// Resize the boxes and end-points arrays when it's full
/// Resize the boxes and end-points arrays when it's full
void resizeArrays();
// Add an overlapping pair of AABBS
/// Add an overlapping pair of AABBS
void addPair(CollisionBody* body1, CollisionBody* body2);
// Check for 1D box intersection
/// Check for 1D box intersection between two boxes that are sorted on the given axis.
bool testIntersect1DSortedAABBs(const BoxAABB& box1, const AABBInt& box2,
const EndPoint* const baseEndPoint, uint axis) const;
// Check for 2D box intersection
/// Check for 2D box intersection.
bool testIntersect2D(const BoxAABB& box1, const BoxAABB& box2,
luint axis1, uint axis2) const;
@ -140,28 +158,28 @@ class SweepAndPruneAlgorithm : public BroadPhaseAlgorithm {
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
SweepAndPruneAlgorithm(CollisionDetection& mCollisionDetection);
// Destructor
/// Destructor
virtual ~SweepAndPruneAlgorithm();
// Notify the broad-phase about a new object in the world
/// Notify the broad-phase about a new object in the world.
virtual void addObject(CollisionBody* body, const AABB& aabb);
// Notify the broad-phase about a object that has been removed from the world
/// Notify the broad-phase about a object that has been removed from the world
virtual void removeObject(CollisionBody* body);
// Notify the broad-phase that the AABB of an object has changed
/// Notify the broad-phase that the AABB of an object has changed
virtual void updateObject(CollisionBody* body, const AABB& aabb);
};
// Encode a floating value into a integer value in order to
// work with integer comparison in the Sweep-And-Prune algorithm
// because it is faster. The main issue when encoding floating
// number into integer is to keep to sorting order. This is a
// problem for negative float number. This article describes
// how to solve this issue : http://www.stereopsis.com/radix.html
/// Encode a floating value into a integer value in order to
/// work with integer comparison in the Sweep-And-Prune algorithm
/// because it is faster. The main issue when encoding floating
/// number into integer is to keep to sorting order. This is a
/// problem for negative float number. This article describes
/// how to solve this issue : http://www.stereopsis.com/radix.html
inline uint encodeFloatIntoInteger(float number) {
uint intNumber = (uint&) number;
@ -176,9 +194,9 @@ inline uint encodeFloatIntoInteger(float number) {
}
// Check for 1D box intersection between two boxes that are sorted on the
// given axis. Therefore, only one test is necessary here. We know that the
// minimum of box1 cannot be larger that the maximum of box2 on the axis.
// Check for 1D box intersection between two boxes that are sorted on the given axis.
/// Therefore, only one test is necessary here. We know that the
/// minimum of box1 cannot be larger that the maximum of box2 on the axis.
inline bool SweepAndPruneAlgorithm::testIntersect1DSortedAABBs(const BoxAABB& box1,
const AABBInt& box2,
const EndPoint* const endPointsArray,
@ -187,15 +205,15 @@ inline bool SweepAndPruneAlgorithm::testIntersect1DSortedAABBs(const BoxAABB& bo
}
// Check for 2D box intersection. This method is used when we know
// that two boxes already overlap on one axis and when want to test
// if they also overlap on the two others axis.
/// that two boxes already overlap on one axis and when want to test
/// if they also overlap on the two others axis.
inline bool SweepAndPruneAlgorithm::testIntersect2D(const BoxAABB& box1, const BoxAABB& box2,
luint axis1, uint axis2) const {
return !(box2.max[axis1] < box1.min[axis1] || box1.max[axis1] < box2.min[axis1] ||
box2.max[axis2] < box1.min[axis2] || box1.max[axis2] < box2.min[axis2]);
}
} // End of reactphysics3d namespace
}
#endif

View File

@ -42,9 +42,9 @@ EPAAlgorithm::~EPAAlgorithm() {
}
// Decide if the origin is in the tetrahedron
// Return 0 if the origin is in the tetrahedron and return the number (1,2,3 or 4) of
// the vertex that is wrong if the origin is not in the tetrahedron
// Decide if the origin is in the tetrahedron.
/// Return 0 if the origin is in the tetrahedron and return the number (1,2,3 or 4) of
/// the vertex that is wrong if the origin is not in the tetrahedron
int EPAAlgorithm::isOriginInTetrahedron(const Vector3& p1, const Vector3& p2,
const Vector3& p3, const Vector3& p4) const {
@ -76,12 +76,12 @@ int EPAAlgorithm::isOriginInTetrahedron(const Vector3& p1, const Vector3& p2,
return 0;
}
// Compute the penetration depth with the EPA algorithms
// This method computes the penetration depth and contact points between two
// enlarged objects (with margin) where the original objects (without margin)
// intersect. An initial simplex that contains origin has been computed with
// GJK algorithm. The EPA Algorithm will extend this simplex polytope to find
// the correct penetration depth
// Compute the penetration depth with the EPA algorithm.
/// This method computes the penetration depth and contact points between two
/// enlarged objects (with margin) where the original objects (without margin)
/// intersect. An initial simplex that contains origin has been computed with
/// GJK algorithm. The EPA Algorithm will extend this simplex polytope to find
/// the correct penetration depth
bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simplex,
const CollisionShape* collisionShape1,
const Transform& transform1,

View File

@ -35,67 +35,75 @@
#include "../../../memory/MemoryPool.h"
#include <algorithm>
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Constants
const unsigned int MAX_SUPPORT_POINTS = 100; // Maximum number of support points of the polytope
const unsigned int MAX_FACETS = 200; // Maximum number of facets of the polytope
// ---------- Constants ---------- //
/// Maximum number of support points of the polytope
const unsigned int MAX_SUPPORT_POINTS = 100;
/// Maximum number of facets of the polytope
const unsigned int MAX_FACETS = 200;
// Class TriangleComparison that allow the comparison of two triangles in the heap
// The comparison between two triangles is made using their square distance to the closest
// point to the origin. The goal is that in the heap, the first triangle is the one with the
// smallest square distance.
// Class TriangleComparison
/**
* This class allows the comparison of two triangles in the heap
* The comparison between two triangles is made using their square distance to the closest
* point to the origin. The goal is that in the heap, the first triangle is the one with the
* smallest square distance.
*/
class TriangleComparison {
public:
// Comparison operator
/// Comparison operator
bool operator()(const TriangleEPA* face1, const TriangleEPA* face2) {
return (face1->getDistSquare() > face2->getDistSquare());
}
};
/* -------------------------------------------------------------------
Class EPAAlgorithm :
This class is the implementation of the Expanding Polytope Algorithm (EPA).
The EPA algorithm computes the penetration depth and contact points between
two enlarged objects (with margin) where the original objects (without margin)
intersect. The penetration depth of a pair of intersecting objects A and B is
the length of a point on the boundary of the Minkowski sum (A-B) closest to the
origin. The goal of the EPA algorithm is to start with an initial simplex polytope
that contains the origin and expend it in order to find the point on the boundary
of (A-B) that is closest to the origin. An initial simplex that contains origin
has been computed wit GJK algorithm. The EPA Algorithm will extend this simplex
polytope to find the correct penetration depth. The implementation of the EPA
algorithm is based on the book "Collision Detection in 3D Environments".
-------------------------------------------------------------------
*/
// Class EPAAlgorithm
/**
* This class is the implementation of the Expanding Polytope Algorithm (EPA).
* The EPA algorithm computes the penetration depth and contact points between
* two enlarged objects (with margin) where the original objects (without margin)
* intersect. The penetration depth of a pair of intersecting objects A and B is
* the length of a point on the boundary of the Minkowski sum (A-B) closest to the
* origin. The goal of the EPA algorithm is to start with an initial simplex polytope
* that contains the origin and expend it in order to find the point on the boundary
* of (A-B) that is closest to the origin. An initial simplex that contains origin
* has been computed wit GJK algorithm. The EPA Algorithm will extend this simplex
* polytope to find the correct penetration depth. The implementation of the EPA
* algorithm is based on the book "Collision Detection in 3D Environments".
*/
class EPAAlgorithm {
private:
// -------------------- Attributes -------------------- //
// Reference to the memory pool
/// Reference to the memory pool
MemoryPool<ContactInfo>& mMemoryPoolContactInfos;
// Triangle comparison operator
/// Triangle comparison operator
TriangleComparison mTriangleComparison;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
EPAAlgorithm(const EPAAlgorithm& algorithm);
// Private assignment operator
/// Private assignment operator
EPAAlgorithm& operator=(const EPAAlgorithm& algorithm);
// Add a triangle face in the candidate triangle heap
/// Add a triangle face in the candidate triangle heap
void addFaceCandidate(TriangleEPA* triangle, TriangleEPA** heap, uint& nbTriangles,
decimal upperBoundSquarePenDepth);
// Decide if the origin is in the tetrahedron
/// Decide if the origin is in the tetrahedron.
int isOriginInTetrahedron(const Vector3& p1, const Vector3& p2,
const Vector3& p3, const Vector3& p4) const;
@ -103,13 +111,13 @@ class EPAAlgorithm {
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
EPAAlgorithm(MemoryPool<ContactInfo>& memoryPoolContactInfos);
// Destructor
/// Destructor
~EPAAlgorithm();
// Compute the penetration depth with EPA algorithm
/// Compute the penetration depth with EPA algorithm.
bool computePenetrationDepthAndContactPoints(const Simplex& simplex,
const CollisionShape* collisionShape1,
const Transform& transform1,

View File

@ -30,64 +30,62 @@
// Libraries
#include "../../../mathematics/mathematics.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Class declarations
class TriangleEPA;
class TrianglesStore;
/* -------------------------------------------------------------------
Class EdgeEPA :
This class represents an edge of the current polytope in the EPA
algorithm.
-------------------------------------------------------------------
*/
// Class EdgeEPA
/**
* This class represents an edge of the current polytope in the EPA algorithm.
*/
class EdgeEPA {
private:
// -------------------- Attributes -------------------- //
// Pointer to the triangle that contains this edge
/// Pointer to the triangle that contains this edge
TriangleEPA* mOwnerTriangle;
// Index of the edge in the triangle (between 0 and 2).
// The edge with index i connect triangle vertices i and (i+1 % 3)
/// Index of the edge in the triangle (between 0 and 2).
/// The edge with index i connect triangle vertices i and (i+1 % 3)
int mIndex;
public:
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
EdgeEPA();
// Constructor
/// Constructor
EdgeEPA(TriangleEPA* ownerTriangle, int index);
// Copy-constructor
/// Copy-constructor
EdgeEPA(const EdgeEPA& edge);
// Destructor
/// Destructor
~EdgeEPA();
// Return the pointer to the owner triangle
/// Return the pointer to the owner triangle
TriangleEPA* getOwnerTriangle() const;
// Return the index of the edge in the triangle
/// Return the index of the edge in the triangle
int getIndex() const;
// Return index of the source vertex of the edge
/// Return index of the source vertex of the edge
uint getSourceVertexIndex() const;
// Return the index of the target vertex of the edge
/// Return the index of the target vertex of the edge
uint getTargetVertexIndex() const;
// Execute the recursive silhouette algorithm from this edge
/// Execute the recursive silhouette algorithm from this edge
bool computeSilhouette(const Vector3* vertices, uint index, TrianglesStore& triangleStore);
// Assignment operator
/// Assignment operator
EdgeEPA& operator=(const EdgeEPA& edge);
};

View File

@ -83,9 +83,9 @@ bool TriangleEPA::computeClosestPoint(const Vector3* vertices) {
return false;
}
// Link an edge with another one (meaning that the current edge of a triangle will
// be associated with the edge of another triangle in order that both triangles
// are neighbour along both edges)
/// Link an edge with another one. It means that the current edge of a triangle will
/// be associated with the edge of another triangle in order that both triangles
/// are neighbour along both edges).
bool reactphysics3d::link(const EdgeEPA& edge0, const EdgeEPA& edge1) {
bool isPossible = (edge0.getSourceVertexIndex() == edge1.getTargetVertexIndex() &&
edge0.getTargetVertexIndex() == edge1.getSourceVertexIndex());
@ -98,10 +98,10 @@ bool reactphysics3d::link(const EdgeEPA& edge0, const EdgeEPA& edge1) {
return isPossible;
}
// Make an half link of an edge with another one from another triangle. An half-link
// between an edge "edge0" and an edge "edge1" represents the fact that "edge1" is an
// adjacent edge of "edge0" but not the opposite. The opposite edge connection will
// be made later.
/// Make an half link of an edge with another one from another triangle. An half-link
/// between an edge "edge0" and an edge "edge1" represents the fact that "edge1" is an
/// adjacent edge of "edge0" but not the opposite. The opposite edge connection will
/// be made later.
void reactphysics3d::halfLink(const EdgeEPA& edge0, const EdgeEPA& edge1) {
assert(edge0.getSourceVertexIndex() == edge1.getTargetVertexIndex() &&
edge0.getTargetVertexIndex() == edge1.getSourceVertexIndex());
@ -110,17 +110,17 @@ void reactphysics3d::halfLink(const EdgeEPA& edge0, const EdgeEPA& edge1) {
edge0.getOwnerTriangle()->mAdjacentEdges[edge0.getIndex()] = edge1;
}
// Execute the recursive silhouette algorithm from this triangle face
// The parameter "vertices" is an array that contains the vertices of the current polytope and the
// parameter "indexNewVertex" is the index of the new vertex in this array. The goal of the
// silhouette algorithm is to add the new vertex in the polytope by keeping it convex. Therefore,
// the triangle faces that are visible from the new vertex must be removed from the polytope and we
// need to add triangle faces where each face contains the new vertex and an edge of the silhouette.
// The silhouette is the connected set of edges that are part of the border between faces that
// are seen and faces that are not seen from the new vertex. This method starts from the nearest
// face from the new vertex, computes the silhouette and create the new faces from the new vertex in
// order that we always have a convex polytope. The faces visible from the new vertex are set
// obselete and will not be considered as being a candidate face in the future.
// Execute the recursive silhouette algorithm from this triangle face.
/// The parameter "vertices" is an array that contains the vertices of the current polytope and the
/// parameter "indexNewVertex" is the index of the new vertex in this array. The goal of the
/// silhouette algorithm is to add the new vertex in the polytope by keeping it convex. Therefore,
/// the triangle faces that are visible from the new vertex must be removed from the polytope and we
/// need to add triangle faces where each face contains the new vertex and an edge of the silhouette.
/// The silhouette is the connected set of edges that are part of the border between faces that
/// are seen and faces that are not seen from the new vertex. This method starts from the nearest
/// face from the new vertex, computes the silhouette and create the new faces from the new vertex in
/// order that we always have a convex polytope. The faces visible from the new vertex are set
/// obselete and will not be considered as being a candidate face in the future.
bool TriangleEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex,
TrianglesStore& triangleStore) {

View File

@ -32,7 +32,7 @@
#include "EdgeEPA.h"
#include <cassert>
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Prototypes
@ -40,103 +40,101 @@ bool link(const EdgeEPA& edge0, const EdgeEPA& edge1);
void halfLink(const EdgeEPA& edge0, const EdgeEPA& edge1);
/* -------------------------------------------------------------------
Class TriangleEPA :
This class represents a triangle face of the current polytope in the EPA
algorithm.
-------------------------------------------------------------------
*/
// Class TriangleEPA
/**
* This class represents a triangle face of the current polytope in the EPA algorithm.
*/
class TriangleEPA {
private:
// -------------------- Attributes -------------------- //
// Indices of the vertices y_i of the triangle
/// Indices of the vertices y_i of the triangle
uint mIndicesVertices[3];
// Three adjacent edges of the triangle (edges of other triangles)
/// Three adjacent edges of the triangle (edges of other triangles)
EdgeEPA mAdjacentEdges[3];
// True if the triangle face is visible from the new support point
/// True if the triangle face is visible from the new support point
bool mIsObsolete;
// Determinant
/// Determinant
decimal mDet;
// Point v closest to the origin on the affine hull of the triangle
/// Point v closest to the origin on the affine hull of the triangle
Vector3 mClosestPoint;
// Lambda1 value such that v = lambda0 * y_0 + lambda1 * y_1 + lambda2 * y_2
/// Lambda1 value such that v = lambda0 * y_0 + lambda1 * y_1 + lambda2 * y_2
decimal mLambda1;
// Lambda1 value such that v = lambda0 * y_0 + lambda1 * y_1 + lambda2 * y_2
/// Lambda1 value such that v = lambda0 * y_0 + lambda1 * y_1 + lambda2 * y_2
decimal mLambda2;
// Square distance of the point closest point v to the origin
/// Square distance of the point closest point v to the origin
decimal mDistSquare;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
TriangleEPA(const TriangleEPA& triangle);
// Private assignment operator
/// Private assignment operator
TriangleEPA& operator=(const TriangleEPA& triangle);
public:
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
TriangleEPA();
// Constructor
/// Constructor
TriangleEPA(uint v1, uint v2, uint v3);
// Destructor
/// Destructor
~TriangleEPA();
// Return an adjacent edge of the triangle
/// Return an adjacent edge of the triangle
EdgeEPA& getAdjacentEdge(int index);
// Set an adjacent edge of the triangle
/// Set an adjacent edge of the triangle
void setAdjacentEdge(int index, EdgeEPA& edge);
// Return the square distance of the closest point to origin
/// Return the square distance of the closest point to origin
decimal getDistSquare() const;
// Set the isObsolete value
/// Set the isObsolete value
void setIsObsolete(bool isObsolete);
// Return true if the triangle face is obsolete
/// Return true if the triangle face is obsolete
bool getIsObsolete() const;
// Return the point closest to the origin
/// Return the point closest to the origin
const Vector3& getClosestPoint() const;
// Return true if the closest point on affine hull is inside the triangle
bool isClosestPointInternalToTriangle() const;
// Return true if the triangle is visible from a given vertex
/// Return true if the triangle is visible from a given vertex
bool isVisibleFromVertex(const Vector3* vertices, uint index) const;
// Compute the point v closest to the origin of this triangle
/// Compute the point v closest to the origin of this triangle
bool computeClosestPoint(const Vector3* vertices);
// Compute the point of an object closest to the origin
/// Compute the point of an object closest to the origin
Vector3 computeClosestPointOfObject(const Vector3* supportPointsOfObject) const;
// Execute the recursive silhouette algorithm from this triangle face
/// Execute the recursive silhouette algorithm from this triangle face.
bool computeSilhouette(const Vector3* vertices, uint index, TrianglesStore& triangleStore);
// Access operator
/// Access operator
uint operator[](int i) const;
// Associate two edges
/// Associate two edges
friend bool link(const EdgeEPA& edge0, const EdgeEPA& edge1);
// Make a half-link between two edges
/// Make a half-link between two edges
friend void halfLink(const EdgeEPA& edge0, const EdgeEPA& edge1);
};

View File

@ -32,65 +32,62 @@
// Libraries
#include <cassert>
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Constants
const unsigned int MAX_TRIANGLES = 200; // Maximum number of triangles
/* -------------------------------------------------------------------
Class TrianglesStore :
This class stores several triangles of the polytope in the EPA
algorithm.
-------------------------------------------------------------------
*/
// Class TriangleStore
/**
* This class stores several triangles of the polytope in the EPA algorithm.
*/
class TrianglesStore {
private:
// -------------------- Attributes -------------------- //
// Triangles
/// Triangles
TriangleEPA mTriangles[MAX_TRIANGLES];
// Number of triangles
/// Number of triangles
int mNbTriangles;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
TrianglesStore(const TrianglesStore& triangleStore);
// Private assignment operator
/// Private assignment operator
TrianglesStore& operator=(const TrianglesStore& triangleStore);
public:
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
TrianglesStore();
// Destructor
/// Destructor
~TrianglesStore();
// Clear all the storage
/// Clear all the storage
void clear();
// Return the number of triangles
/// Return the number of triangles
int getNbTriangles() const;
// Set the number of triangles
/// Set the number of triangles
void setNbTriangles(int backup);
// Return the last triangle
/// Return the last triangle
TriangleEPA& last();
// Create a new triangle
/// Create a new triangle
TriangleEPA* newTriangle(const Vector3* vertices, uint v0, uint v1, uint v2);
// Access operator
/// Access operator
TriangleEPA& operator[](int i);
};

View File

@ -47,16 +47,16 @@ GJKAlgorithm::~GJKAlgorithm() {
}
// Return true and compute a contact info if the two bounding volume collide.
// This method implements the Hybrid Technique for computing the penetration depth by
// running the GJK algorithm on original objects (without margin).
// If the objects don't intersect, this method returns false. If they intersect
// only in the margins, the method compute the penetration depth and contact points
// (of enlarged objects). If the original objects (without margin) intersect, we
// call the computePenetrationDepthForEnlargedObjects() method that run the GJK
// algorithm on the enlarged object to obtain a simplex polytope that contains the
// origin, they we give that simplex polytope to the EPA algorithm which will compute
// the correct penetration depth and contact points between the enlarged objects.
// Return true and compute a contact info if the two bounding volumes collide.
/// This method implements the Hybrid Technique for computing the penetration depth by
/// running the GJK algorithm on original objects (without margin).
/// If the objects don't intersect, this method returns false. If they intersect
/// only in the margins, the method compute the penetration depth and contact points
/// (of enlarged objects). If the original objects (without margin) intersect, we
/// call the computePenetrationDepthForEnlargedObjects() method that run the GJK
/// algorithm on the enlarged object to obtain a simplex polytope that contains the
/// origin, they we give that simplex polytope to the EPA algorithm which will compute
/// the correct penetration depth and contact points between the enlarged objects.
bool GJKAlgorithm::testCollision(const CollisionShape* collisionShape1,
const Transform& transform1,
const CollisionShape* collisionShape2,
@ -254,11 +254,11 @@ bool GJKAlgorithm::testCollision(const CollisionShape* collisionShape1,
transform2, contactInfo, v);
}
// This method runs the GJK algorithm on the two enlarged objects (with margin)
// to compute a simplex polytope that contains the origin. The two objects are
// assumed to intersect in the original objects (without margin). Therefore such
// a polytope must exist. Then, we give that polytope to the EPA algorithm to
// compute the correct penetration depth and contact points of the enlarged objects.
/// This method runs the GJK algorithm on the two enlarged objects (with margin)
/// to compute a simplex polytope that contains the origin. The two objects are
/// assumed to intersect in the original objects (without margin). Therefore such
/// a polytope must exist. Then, we give that polytope to the EPA algorithm to
/// compute the correct penetration depth and contact points of the enlarged objects.
bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShape* collisionShape1,
const Transform& transform1,
const CollisionShape* collisionShape2,

View File

@ -33,48 +33,47 @@
#include "../EPA/EPAAlgorithm.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Constants
const decimal REL_ERROR = decimal(1.0e-3);
const decimal REL_ERROR_SQUARE = REL_ERROR * REL_ERROR;
/* -------------------------------------------------------------------
Class GJKAlgorithm :
This class implements a narrow-phase collision detection algorithm. This
algorithm uses the ISA-GJK algorithm and the EPA algorithm. This
implementation is based on the implementation discussed in the book
"Collision Detection in 3D Environments".
This method implements the Hybrid Technique for calculating the
penetration depth. The two objects are enlarged with a small margin. If
the object intersection, the penetration depth is quickly computed using
GJK algorithm on the original objects (without margin). If the
original objects (without margin) intersect, we run again the GJK
algorithm on the enlarged objects (with margin) to compute simplex
polytope that contains the origin and give it to the EPA (Expanding
Polytope Algorithm) to compute the correct penetration depth between the
enlarged objects.
-------------------------------------------------------------------
*/
// Class GJKAlgorithm
/**
* This class implements a narrow-phase collision detection algorithm. This
* algorithm uses the ISA-GJK algorithm and the EPA algorithm. This
* implementation is based on the implementation discussed in the book
* "Collision Detection in 3D Environments".
* This method implements the Hybrid Technique for calculating the
* penetration depth. The two objects are enlarged with a small margin. If
* the object intersection, the penetration depth is quickly computed using
* GJK algorithm on the original objects (without margin). If the
* original objects (without margin) intersect, we run again the GJK
* algorithm on the enlarged objects (with margin) to compute simplex
* polytope that contains the origin and give it to the EPA (Expanding
* Polytope Algorithm) to compute the correct penetration depth between the
* enlarged objects.
*/
class GJKAlgorithm : public NarrowPhaseAlgorithm {
private :
// -------------------- Attributes -------------------- //
// EPA Algorithm
/// EPA Algorithm
EPAAlgorithm mAlgoEPA;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
GJKAlgorithm(const GJKAlgorithm& algorithm);
// Private assignment operator
/// Private assignment operator
GJKAlgorithm& operator=(const GJKAlgorithm& algorithm);
// Compute the penetration depth for enlarged objects
/// Compute the penetration depth for enlarged objects.
bool computePenetrationDepthForEnlargedObjects(const CollisionShape* collisionShape1,
const Transform& transform1,
const CollisionShape* collisionShape2,
@ -85,13 +84,13 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm {
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
GJKAlgorithm(MemoryPool<ContactInfo>& memoryPoolContactInfos);
// Destructor
/// Destructor
~GJKAlgorithm();
// Return true and compute a contact info if the two bounding volume collide
/// Return true and compute a contact info if the two bounding volumes collide.
virtual bool testCollision(const CollisionShape* collisionShape1,
const Transform& transform1,
const CollisionShape* collisionShape2,

View File

@ -41,9 +41,9 @@ Simplex::~Simplex() {
}
// Add a new support point of (A-B) into the simplex
// suppPointA : support point of object A in a direction -v
// suppPointB : support point of object B in a direction v
// point : support point of object (A-B) => point = suppPointA - suppPointB
/// suppPointA : support point of object A in a direction -v
/// suppPointB : support point of object B in a direction v
/// point : support point of object (A-B) => point = suppPointA - suppPointB
void Simplex::addPoint(const Vector3& point, const Vector3& suppPointA, const Vector3& suppPointB) {
assert(!isFull());
@ -220,9 +220,9 @@ void Simplex::computeDeterminants() {
}
}
// Return true if the subset is a proper subset
// A proper subset X is a subset where for all point "y_i" in X, we have
// detX_i value bigger than zero
// Return true if the subset is a proper subset.
/// A proper subset X is a subset where for all point "y_i" in X, we have
/// detX_i value bigger than zero
bool Simplex::isProperSubset(Bits subset) const {
int i;
Bits bit;
@ -237,8 +237,9 @@ bool Simplex::isProperSubset(Bits subset) const {
return true;
}
// Return true if the set is affinely dependent meaning that a point of the set
// is an affine combination of other points in the set
// Return true if the set is affinely dependent.
/// A set if affinely dependent if a point of the set
/// is an affine combination of other points in the set
bool Simplex::isAffinelyDependent() const {
decimal sum = 0.0;
int i;
@ -254,10 +255,10 @@ bool Simplex::isAffinelyDependent() const {
return (sum <= 0.0);
}
// Return true if the subset is a valid one for the closest point computation
// A subset X is valid if :
// 1. delta(X)_i > 0 for each "i" in I_x and
// 2. delta(X U {y_j})_j <= 0 for each "j" not in I_x_
// Return true if the subset is a valid one for the closest point computation.
/// A subset X is valid if :
/// 1. delta(X)_i > 0 for each "i" in I_x and
/// 2. delta(X U {y_j})_j <= 0 for each "j" not in I_x_
bool Simplex::isValidSubset(Bits subset) const {
int i;
Bits bit;
@ -285,11 +286,11 @@ bool Simplex::isValidSubset(Bits subset) const {
return true;
}
// Compute the closest points "pA" and "pB" of object A and B
// The points are computed as follows :
// pA = sum(lambda_i * a_i) where "a_i" are the support points of object A
// pB = sum(lambda_i * b_i) where "b_i" are the support points of object B
// with lambda_i = deltaX_i / deltaX
// Compute the closest points "pA" and "pB" of object A and B.
/// The points are computed as follows :
/// pA = sum(lambda_i * a_i) where "a_i" are the support points of object A
/// pB = sum(lambda_i * b_i) where "b_i" are the support points of object B
/// with lambda_i = deltaX_i / deltaX
void Simplex::computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) const {
decimal deltaX = 0.0;
pA.setAllValues(0.0, 0.0, 0.0);
@ -313,10 +314,10 @@ void Simplex::computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) const {
pB *= factor;
}
// Compute the closest point "v" to the origin of the current simplex
// This method executes the Jonhnson's algorithm for computing the point
// "v" of simplex that is closest to the origin. The method returns true
// if a closest point has been found.
// Compute the closest point "v" to the origin of the current simplex.
/// This method executes the Jonhnson's algorithm for computing the point
/// "v" of simplex that is closest to the origin. The method returns true
/// if a closest point has been found.
bool Simplex::computeClosestPoint(Vector3& v) {
Bits subset;

View File

@ -30,133 +30,132 @@
#include "../../../mathematics/mathematics.h"
#include <vector>
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Type definitions
typedef unsigned int Bits;
/* -------------------------------------------------------------------
Class Simplex :
This class represents a simplex which is a set of 3D points. This
class is used in the GJK algorithm. This implementation is based on
the implementation discussed in the book "Collision Detection in 3D
Environments". This class implements the Johnson's algorithm for
computing the point of a simplex that is closest to the origin and also
the smallest simplex needed to represent that closest point.
-------------------------------------------------------------------
*/
// Class Simplex
/**
* This class represents a simplex which is a set of 3D points. This
* class is used in the GJK algorithm. This implementation is based on
* the implementation discussed in the book "Collision Detection in 3D
* Environments". This class implements the Johnson's algorithm for
* computing the point of a simplex that is closest to the origin and also
* the smallest simplex needed to represent that closest point.
*/
class Simplex {
private:
// -------------------- Attributes -------------------- //
// Current points
/// Current points
Vector3 mPoints[4];
// pointsLengthSquare[i] = (points[i].length)^2
/// pointsLengthSquare[i] = (points[i].length)^2
decimal mPointsLengthSquare[4];
// Maximum length of pointsLengthSquare[i]
/// Maximum length of pointsLengthSquare[i]
decimal mMaxLengthSquare;
// Support points of object A in local coordinates
/// Support points of object A in local coordinates
Vector3 mSuppPointsA[4];
// Support points of object B in local coordinates
/// Support points of object B in local coordinates
Vector3 mSuppPointsB[4];
// diff[i][j] contains points[i] - points[j]
/// diff[i][j] contains points[i] - points[j]
Vector3 mDiffLength[4][4];
// Cached determinant values
/// Cached determinant values
decimal mDet[16][4];
// norm[i][j] = (diff[i][j].length())^2
/// norm[i][j] = (diff[i][j].length())^2
decimal mNormSquare[4][4];
// 4 bits that identify the current points of the simplex
// For instance, 0101 means that points[1] and points[3] are in the simplex
/// 4 bits that identify the current points of the simplex
/// For instance, 0101 means that points[1] and points[3] are in the simplex
Bits mBitsCurrentSimplex;
// Number between 1 and 4 that identify the last found support point
/// Number between 1 and 4 that identify the last found support point
Bits mLastFound;
// Position of the last found support point (lastFoundBit = 0x1 << lastFound)
/// Position of the last found support point (lastFoundBit = 0x1 << lastFound)
Bits mLastFoundBit;
// allBits = bitsCurrentSimplex | lastFoundBit;
/// allBits = bitsCurrentSimplex | lastFoundBit;
Bits mAllBits;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
Simplex(const Simplex& simplex);
// Private assignment operator
/// Private assignment operator
Simplex& operator=(const Simplex& simplex);
// Return true if some bits of "a" overlap with bits of "b"
/// Return true if some bits of "a" overlap with bits of "b"
bool overlap(Bits a, Bits b) const;
// Return true if the bits of "b" is a subset of the bits of "a"
/// Return true if the bits of "b" is a subset of the bits of "a"
bool isSubset(Bits a, Bits b) const;
// Return true if the subset is a valid one for the closest point computation
/// Return true if the subset is a valid one for the closest point computation.
bool isValidSubset(Bits subset) const;
// Return true if the subset is a proper subset
/// Return true if the subset is a proper subset.
bool isProperSubset(Bits subset) const;
// Update the cached values used during the GJK algorithm
/// Update the cached values used during the GJK algorithm
void updateCache();
// Compute the cached determinant values
/// Compute the cached determinant values
void computeDeterminants();
// Return the closest point "v" in the convex hull of a subset of points
/// Return the closest point "v" in the convex hull of a subset of points
Vector3 computeClosestPointForSubset(Bits subset);
public:
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
Simplex();
// Destructor
/// Destructor
~Simplex();
// Return true if the simplex contains 4 points
/// Return true if the simplex contains 4 points
bool isFull() const;
// Return true if the simple is empty
/// Return true if the simple is empty
bool isEmpty() const;
// Return the points of the simplex
/// Return the points of the simplex
unsigned int getSimplex(Vector3* mSuppPointsA, Vector3* mSuppPointsB,
Vector3* mPoints) const;
// Return the maximum squared length of a point
/// Return the maximum squared length of a point
decimal getMaxLengthSquareOfAPoint() const;
// Addd a point to the simplex
/// Add a new support point of (A-B) into the simplex.
void addPoint(const Vector3& point, const Vector3& suppPointA, const Vector3& suppPointB);
// Return true if the point is in the simplex
/// Return true if the point is in the simplex
bool isPointInSimplex(const Vector3& point) const;
// Return true if the set is affinely dependent
/// Return true if the set is affinely dependent
bool isAffinelyDependent() const;
// Backup the closest point
/// Backup the closest point
void backupClosestPointInSimplex(Vector3& point);
// Compute the closest points of object A and B
/// Compute the closest points "pA" and "pB" of object A and B.
void computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) const;
// Compute the closest point to the origin of the current simplex
/// Compute the closest point to the origin of the current simplex.
bool computeClosestPoint(Vector3& v);
};

View File

@ -34,52 +34,50 @@
#include "../BroadPhasePair.h"
// Namespace ReactPhysics3D
/// Namespace ReactPhysics3D
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class NarrowPhaseAlgorithm :
This class is an abstract class that represents an algorithm
used to perform the narrow-phase of a collision detection. The
goal of the narrow phase algorithm is to compute contact
informations of a collision between two bodies.
-------------------------------------------------------------------
*/
// Class NarrowPhaseAlgorithm
/**
* This class is an abstract class that represents an algorithm
* used to perform the narrow-phase of a collision detection. The
* goal of the narrow phase algorithm is to compute contact
* informations of a collision between two bodies.
*/
class NarrowPhaseAlgorithm {
protected :
// -------------------- Attributes -------------------- //
// Reference to the memory pool
/// Reference to the memory pool
MemoryPool<ContactInfo>& mMemoryPoolContactInfos;
// Overlapping pair of the bodies currently tested for collision
/// Overlapping pair of the bodies currently tested for collision
BroadPhasePair* mCurrentOverlappingPair;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
NarrowPhaseAlgorithm(const NarrowPhaseAlgorithm& algorithm);
// Private assignment operator
/// Private assignment operator
NarrowPhaseAlgorithm& operator=(const NarrowPhaseAlgorithm& algorithm);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
NarrowPhaseAlgorithm(MemoryPool<ContactInfo>& memoryPool);
// Destructor
/// Destructor
virtual ~NarrowPhaseAlgorithm();
// Set the current overlapping pair of bodies
/// Set the current overlapping pair of bodies
void setCurrentOverlappingPair(BroadPhasePair* overlappingPair);
// Return true and compute a contact info if the two bounding volume collide
/// Return true and compute a contact info if the two bounding volume collide
virtual bool testCollision(const CollisionShape* collisionShape1,
const Transform& transform1,
const CollisionShape* collisionShape2,

View File

@ -32,38 +32,37 @@
#include "NarrowPhaseAlgorithm.h"
// Namespace ReactPhysics3D
/// Namespace ReactPhysics3D
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class SphereVsSphereAlgorithm :
This class is used to compute the narrow-phase collision detection
between two sphere collision shapes.
-------------------------------------------------------------------
*/
// Class SphereVsSphereAlgorithm
/**
* This class is used to compute the narrow-phase collision detection
* between two sphere collision shapes.
*/
class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm {
protected :
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
SphereVsSphereAlgorithm(const SphereVsSphereAlgorithm& algorithm);
// Private assignment operator
/// Private assignment operator
SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
SphereVsSphereAlgorithm(MemoryPool<ContactInfo>& memoryPoolContactInfos);
// Destructor
/// Destructor
virtual ~SphereVsSphereAlgorithm();
// Return true and compute a contact info if the two bounding volume collide
/// Return true and compute a contact info if the two bounding volume collide
virtual bool testCollision(const CollisionShape* collisionShape1,
const Transform& transform1,
const CollisionShape* collisionShape2,

View File

@ -29,84 +29,83 @@
// Libraries
#include "../../mathematics/mathematics.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Declaration
class Body;
/* -------------------------------------------------------------------
Class AABB :
This class represents a bounding volume of type "Axis Aligned
Bounding Box". It's a box where all the edges are always aligned
with the world coordinate system. The AABB is defined by the
minimum and maximum world coordinates of the three axis.
-------------------------------------------------------------------
*/
// Class AABB
/**
* This class represents a bounding volume of type "Axis Aligned
* Bounding Box". It's a box where all the edges are always aligned
* with the world coordinate system. The AABB is defined by the
* minimum and maximum world coordinates of the three axis.
*/
class AABB {
private :
// -------------------- Attributes -------------------- //
// Minimum world coordinates of the AABB on the x,y and z axis
/// Minimum world coordinates of the AABB on the x,y and z axis
Vector3 mMinCoordinates;
// Maximum world coordinates of the AABB on the x,y and z axis
/// Maximum world coordinates of the AABB on the x,y and z axis
Vector3 mMaxCoordinates;
// Pointer to the owner body (not the abstract class Body
// but its derivative which is instanciable)
/// Pointer to the owner body (not the abstract class Body
/// but its derivative which is instanciable)
Body* mBodyPointer;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
AABB(const AABB& aabb);
// Private assignment operator
/// Private assignment operator
AABB& operator=(const AABB& aabb);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
AABB();
// Constructor
/// Constructor
AABB(const Vector3& minCoordinates, const Vector3& maxCoordinates, Body* modyPointer);
// Constructor
/// Constructor
AABB(const Transform& transform, const Vector3& extents);
// Destructor
/// Destructor
virtual ~AABB();
// Return the center point
/// Return the center point
Vector3 getCenter() const;
// Return the minimum coordinates of the AABB
/// Return the minimum coordinates of the AABB
const Vector3& getMin() const;
// Return the maximum coordinates of the AABB
/// Return the maximum coordinates of the AABB
const Vector3& getMax() const;
// Return a pointer to the owner body
/// Return a pointer to the owner body
Body* getBodyPointer() const;
// Set the body pointer
/// Set the body pointer
void setBodyPointer(Body* bodyPointer);
// Return true if the current AABB is overlapping is the AABB in argument
/// Return true if the current AABB is overlapping with the AABB in argument
bool testCollision(const AABB& aabb) const;
// Update the oriented bounding box orientation
// according to a new orientation of the rigid body
/// Update the oriented bounding box orientation
/// according to a new orientation of the rigid body
virtual void update(const Transform& newTransform, const Vector3& extents);
#ifdef VISUAL_DEBUG
// Draw the AABB (only for testing purpose)
/// Draw the AABB (only for testing purpose)
virtual void draw() const;
#endif
};
@ -136,8 +135,8 @@ inline void AABB::setBodyPointer(Body* bodyPointer) {
mBodyPointer = bodyPointer;
}
// Return true if the current AABB is overlapping with the AABB in argument
// Two AABB overlap if they overlap in the three x, y and z axis at the same time
// Return true if the current AABB is overlapping with the AABB in argument.
/// Two AABBs overlap if they overlap in the three x, y and z axis at the same time
inline bool AABB::testCollision(const AABB& aabb) const {
if (mMaxCoordinates.x < aabb.mMinCoordinates.x ||
aabb.mMaxCoordinates.x < mMinCoordinates.x) return false;

View File

@ -32,67 +32,66 @@
#include "../../mathematics/mathematics.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class BoxShape :
This class represents a 3D box shape. Those axis are unit length.
The three extents are half-widths of the box along the three
axis x, y, z local axis. The "transform" of the corresponding
rigid body gives an orientation and a position to the box.
-------------------------------------------------------------------
*/
// Class BoxShape
/**
* This class represents a 3D box shape. Those axis are unit length.
* The three extents are half-widths of the box along the three
* axis x, y, z local axis. The "transform" of the corresponding
* rigid body gives an orientation and a position to the box.
*/
class BoxShape : public CollisionShape {
private :
// -------------------- Attributes -------------------- //
// Extent sizes of the box in the x, y and z direction
/// Extent sizes of the box in the x, y and z direction
Vector3 mExtent;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
BoxShape(const BoxShape& shape);
// Private assignment operator
/// Private assignment operator
BoxShape& operator=(const BoxShape& shape);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
BoxShape(const Vector3& extent);
// Destructor
/// Destructor
virtual ~BoxShape();
// Return the extents of the box
/// Return the extents of the box
const Vector3& getExtent() const;
// Set the extents of the box
/// Set the extents of the box
void setExtent(const Vector3& extent);
// Return the local extents in x,y and z direction
/// Return the local extents in x,y and z direction.
virtual Vector3 getLocalExtents(decimal margin=0.0) const;
// Return the margin distance around the shape
/// Return the margin distance around the shape
virtual decimal getMargin() const;
// Return a local support point in a given direction with the object margin
/// Return a local support point in a given direction with the object margin
virtual Vector3 getLocalSupportPointWithMargin(const Vector3& direction) const;
// Return a local support point in a given direction without the object margin
/// Return a local support point in a given direction without the object margin
virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const;
// Return the local inertia tensor of the collision shape
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const;
#ifdef VISUAL_DEBUG
// Draw the Box (only for testing purpose)
/// Draw the Box (only for testing purpose)
virtual void draw() const;
#endif
};
@ -107,8 +106,8 @@ inline void BoxShape::setExtent(const Vector3& extent) {
this->mExtent = extent;
}
// Return the local extents of the box (half-width) in x,y and z local direction
// This method is used to compute the AABB of the box
// Return the local extents of the box (half-width) in x,y and z local direction.
/// This method is used to compute the AABB of the box
inline Vector3 BoxShape::getLocalExtents(decimal margin) const {
return mExtent + Vector3(getMargin(), getMargin(), getMargin());
}

View File

@ -31,64 +31,63 @@
#include "../../mathematics/Vector3.h"
#include "../../mathematics/Matrix3x3.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Enumeration
enum CollisionShapeType {BOX, SPHERE, CONE, CYLINDER}; // Type of the collision shape
/// Type of the collision shape
enum CollisionShapeType {BOX, SPHERE, CONE, CYLINDER};
// Declarations
class Body;
/* -------------------------------------------------------------------
Class CollisionShape :
This abstract class represents the collision shape associated with a
body that is used during the narrow-phase collision detection.
-------------------------------------------------------------------
*/
// Class CollisionShape
/**
* This abstract class represents the collision shape associated with a
* body that is used during the narrow-phase collision detection.
*/
class CollisionShape {
protected :
// -------------------- Attributes -------------------- //
// Type of the collision shape
/// Type of the collision shape
CollisionShapeType mType;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
CollisionShape(const CollisionShape& shape);
// Private assignment operator
/// Private assignment operator
CollisionShape& operator=(const CollisionShape& shape);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
CollisionShape(CollisionShapeType type);
// Destructor
/// Destructor
virtual ~CollisionShape();
// Return the type of the collision shapes
/// Return the type of the collision shapes
CollisionShapeType getType() const;
// Return a local support point in a given direction with the object margin
/// Return a local support point in a given direction with the object margin
virtual Vector3 getLocalSupportPointWithMargin(const Vector3& direction) const=0;
// Return a local support point in a given direction without the object margin
/// Return a local support point in a given direction without the object margin
virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const=0;
// Return the local extents in x,y and z direction
/// Return the local extents in x,y and z direction
virtual Vector3 getLocalExtents(decimal margin=0.0) const=0;
// Return the margin distance around the shape
/// Return the margin distance around the shape
virtual decimal getMargin() const=0;
// Return the local inertia tensor of the collision shapes
/// Return the local inertia tensor of the collision shapes
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const=0;
};

View File

@ -30,81 +30,80 @@
#include "CollisionShape.h"
#include "../../mathematics/mathematics.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class ConeShape :
This class represents a cone collision shape centered at the
origin and alligned with the Y axis. The cone is defined
by its height and by the radius of its base. The center of the
cone is at the half of the height. The "transform" of the
corresponding rigid body gives an orientation and a position
to the cone.
-------------------------------------------------------------------
*/
// Class ConeShape
/**
* This class represents a cone collision shape centered at the
* origin and alligned with the Y axis. The cone is defined
* by its height and by the radius of its base. The center of the
* cone is at the half of the height. The "transform" of the
* corresponding rigid body gives an orientation and a position
* to the cone.
*/
class ConeShape : public CollisionShape {
private :
// -------------------- Attributes -------------------- //
// Radius of the base
/// Radius of the base
decimal mRadius;
// Half height of the cone
/// Half height of the cone
decimal mHalfHeight;
// sine of the semi angle at the apex point
/// sine of the semi angle at the apex point
decimal mSinTheta;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
ConeShape(const ConeShape& shape);
// Private assignment operator
/// Private assignment operator
ConeShape& operator=(const ConeShape& shape);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
ConeShape(decimal mRadius, decimal height);
// Destructor
/// Destructor
virtual ~ConeShape();
// Return the radius
/// Return the radius
decimal getRadius() const;
// Set the radius
/// Set the radius
void setRadius(decimal radius);
// Return the height
/// Return the height
decimal getHeight() const;
// Set the height
/// Set the height
void setHeight(decimal height);
// Return a local support point in a given direction with the object margin
/// Return a local support point in a given direction with the object margin
virtual Vector3 getLocalSupportPointWithMargin(const Vector3& direction) const;
// Return a local support point in a given direction without the object margin
/// Return a local support point in a given direction without the object margin
virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const;
// Return the local extents in x,y and z direction
/// Return the local extents in x,y and z direction
virtual Vector3 getLocalExtents(decimal margin=0.0) const;
// Return the local inertia tensor of the collision shape
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const;
// Return the margin distance around the shape
/// Return the margin distance around the shape
virtual decimal getMargin() const;
#ifdef VISUAL_DEBUG
// Draw the sphere (only for testing purpose)
/// Draw the sphere (only for testing purpose)
virtual void draw() const;
#endif
};

View File

@ -31,76 +31,75 @@
#include "../../mathematics/mathematics.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class CylinderShape :
This class represents a cylinder collision shape around the Y axis
and centered at the origin. The cylinder is defined by its height
and the radius of its base. The "transform" of the corresponding
rigid body gives an orientation and a position to the cylinder.
-------------------------------------------------------------------
*/
// Class CylinderShape
/**
* This class represents a cylinder collision shape around the Y axis
* and centered at the origin. The cylinder is defined by its height
* and the radius of its base. The "transform" of the corresponding
* rigid body gives an orientation and a position to the cylinder.
*/
class CylinderShape : public CollisionShape {
private :
// -------------------- Attributes -------------------- //
// Radius of the base
/// Radius of the base
decimal mRadius;
// Half height of the cone
/// Half height of the cone
decimal mHalfHeight;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
CylinderShape(const CylinderShape& shape);
// Private assignment operator
/// Private assignment operator
CylinderShape& operator=(const CylinderShape& shape);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
CylinderShape(decimal radius, decimal height);
// Destructor
/// Destructor
virtual ~CylinderShape();
// Return the radius
/// Return the radius
decimal getRadius() const;
// Set the radius
/// Set the radius
void setRadius(decimal mRadius);
// Return the height
/// Return the height
decimal getHeight() const;
// Set the height
/// Set the height
void setHeight(decimal height);
// Return a local support point in a given direction with the object margin
/// Return a local support point in a given direction with the object margin
virtual Vector3 getLocalSupportPointWithMargin(const Vector3& direction) const;
// Return a local support point in a given direction without the object margin
/// Return a local support point in a given direction without the object margin
virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const;
// Return the local extents in x,y and z direction
/// Return the local extents in x,y and z direction
virtual Vector3 getLocalExtents(decimal margin=0.0) const;
// Return the local inertia tensor of the collision shape
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const;
// Return the margin distance around the shape
/// Return the margin distance around the shape
virtual decimal getMargin() const;
#ifdef VISUAL_DEBUG
// Draw the sphere (only for testing purpose)
/// Draw the sphere (only for testing purpose)
virtual void draw() const;
#endif
};

View File

@ -33,62 +33,61 @@
// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class SphereShape :
This class represents a sphere collision shape that is centered
at the origin and defined by its radius.
-------------------------------------------------------------------
*/
// Class SphereShape
/**
* This class represents a sphere collision shape that is centered
* at the origin and defined by its radius.
*/
class SphereShape : public CollisionShape {
private :
// -------------------- Attributes -------------------- //
// Radius of the sphere
/// Radius of the sphere
decimal mRadius;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
SphereShape(const SphereShape& shape);
// Private assignment operator
/// Private assignment operator
SphereShape& operator=(const SphereShape& shape);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
SphereShape(decimal radius);
// Destructor
/// Destructor
virtual ~SphereShape();
// Return the radius of the sphere
/// Return the radius of the sphere
decimal getRadius() const;
// Set the radius of the sphere
/// Set the radius of the sphere
void setRadius(decimal radius);
// Return a local support point in a given direction with the object margin
/// Return a local support point in a given direction with the object margin
virtual Vector3 getLocalSupportPointWithMargin(const Vector3& direction) const;
// Return a local support point in a given direction without the object margin
/// Return a local support point in a given direction without the object margin
virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const;
// Return the local extents in x,y and z direction
/// Return the local extents in x,y and z direction
virtual Vector3 getLocalExtents(decimal margin=0.0) const;
// Return the local inertia tensor of the collision shape
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const;
// Return the margin distance around the shape
/// Return the margin distance around the shape
virtual decimal getMargin() const;
#ifdef VISUAL_DEBUG
// Draw the sphere (only for testing purpose)
/// Draw the sphere (only for testing purpose)
virtual void draw() const;
#endif
};

View File

@ -41,7 +41,7 @@
#define LINUX_OS
#endif
// Namespace reactphysics3d
/// Namespace reactphysics3d
namespace reactphysics3d {
// ------------------- Type definitions ------------------- //
@ -53,35 +53,37 @@ typedef std::pair<bodyindex, bodyindex> bodyindexpair;
// ------------------- Constants ------------------- //
/// Smallest decimal value (negative)
const decimal DECIMAL_SMALLEST = - std::numeric_limits<decimal>::max();
// Maximum decimal value
/// Maximum decimal value
const decimal DECIMAL_LARGEST = std::numeric_limits<decimal>::max();
// Machine epsilon
/// Machine epsilon
const decimal MACHINE_EPSILON = std::numeric_limits<decimal>::epsilon();
// Pi constant
/// Pi constant
const decimal PI = decimal(3.14159265);
// Default internal constant timestep in seconds
/// Default internal constant timestep in seconds
const decimal DEFAULT_TIMESTEP = decimal(1.0 / 60.0);
// Default friction coefficient for a rigid body
/// Default friction coefficient for a rigid body
const decimal DEFAULT_FRICTION_COEFFICIENT = decimal(0.3);
// True if the deactivation (sleeping) of inactive bodies is enabled
/// True if the deactivation (sleeping) of inactive bodies is enabled
const bool DEACTIVATION_ENABLED = true;
// // Object margin for collision detection in cm (For GJK-EPA Algorithm)
///Object margin for collision detection in cm (For GJK-EPA Algorithm)
const decimal OBJECT_MARGIN = decimal(0.04);
// Distance threshold for two contact points for a valid persistent contact (in meters)
/// Distance threshold for two contact points for a valid persistent contact (in meters)
const decimal PERSISTENT_CONTACT_DIST_THRESHOLD = decimal(0.03);
/// Velocity threshold for contact velocity restitution
const decimal RESTITUTION_VELOCITY_THRESHOLD = decimal(1.0);
// Number of iterations when solving a LCP problem
/// Number of iterations when solving a LCP problem
const uint DEFAULT_CONSTRAINTS_SOLVER_NB_ITERATIONS = 15;
}

View File

@ -26,7 +26,6 @@
// Libraries
#include "Constraint.h"
// We want ot use the ReactPhysics3D namespace
using namespace reactphysics3d;
// Constructor

View File

@ -36,77 +36,76 @@ namespace reactphysics3d {
// Enumeration for the type of a constraint
enum ConstraintType {CONTACT};
/* -------------------------------------------------------------------
Class Constraint :
This abstract class represents a constraint in the physics engine.
A constraint can be a collision contact or a joint for
instance. Each constraint can be made of several "mathematical
constraints" needed to represent the main constraint.
-------------------------------------------------------------------
*/
// Class Constraint
/**
* This abstract class represents a constraint in the physics engine.
* A constraint can be a collision contact or a joint for
* instance. Each constraint can be made of several "mathematical
* constraints" needed to represent the main constraint.
*/
class Constraint {
protected :
// -------------------- Attributes -------------------- //
// Pointer to the first body of the constraint
/// Pointer to the first body of the constraint
RigidBody* const mBody1;
// Pointer to the second body of the constraint
/// Pointer to the second body of the constraint
RigidBody* const mBody2;
// True if the constraint is active
/// True if the constraint is active
bool mActive;
// Number mathematical constraints associated with this Constraint
/// Number mathematical constraints associated with this Constraint
uint mNbConstraints;
// Type of the constraint
/// Type of the constraint
const ConstraintType mType;
// Cached lambda values of each mathematical constraint for
// more precise initializaton of LCP solver
/// Cached lambda values of each mathematical constraint for
/// more precise initializaton of LCP solver
std::vector<decimal> mCachedLambdas;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
Constraint(const Constraint& constraint);
// Private assignment operator
/// Private assignment operator
Constraint& operator=(const Constraint& constraint);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
Constraint(RigidBody* const body1, RigidBody* const body2, uint nbConstraints,
bool active, ConstraintType type);
// Destructor
/// Destructor
virtual ~Constraint();
// Return the reference to the body 1
/// Return the reference to the body 1
RigidBody* const getBody1() const;
// Return the reference to the body 2
/// Return the reference to the body 2
RigidBody* const getBody2() const;
// Return true if the constraint is active
/// Return true if the constraint is active
bool isActive() const;
// Return the type of the constraint
/// Return the type of the constraint
ConstraintType getType() const;
// Return the number of mathematical constraints
/// Return the number of mathematical constraints
unsigned int getNbConstraints() const;
// Get one cached lambda value
/// Get one cached lambda value
decimal getCachedLambda(int index) const;
// Set on cached lambda value
/// Set on cached lambda value
void setCachedLambda(int index, decimal lambda);
};

View File

@ -48,111 +48,110 @@
#endif
#endif
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class ContactPoint :
This class represents a collision contact point between two
bodies in the physics engine. The ContactPoint class inherits from
the Constraint class.
-------------------------------------------------------------------
*/
// Class ContactPoint
/**
* This class represents a collision contact point between two
* bodies in the physics engine. The ContactPoint class inherits from
* the Constraint class.
*/
class ContactPoint : public Constraint {
protected :
// -------------------- Attributes -------------------- //
// Normal vector of the contact (From body1 toward body2) in world space
/// Normal vector of the contact (From body1 toward body2) in world space
const Vector3 mNormal;
// Penetration depth
/// Penetration depth
decimal mPenetrationDepth;
// Contact point on body 1 in local space of body 1
/// Contact point on body 1 in local space of body 1
const Vector3 mLocalPointOnBody1;
// Contact point on body 2 in local space of body 2
/// Contact point on body 2 in local space of body 2
const Vector3 mLocalPointOnBody2;
// Contact point on body 1 in world space
/// Contact point on body 1 in world space
Vector3 mWorldPointOnBody1;
// Contact point on body 2 in world space
/// Contact point on body 2 in world space
Vector3 mWorldPointOnBody2;
// True if the contact is a resting contact (exists for more than one time step)
/// True if the contact is a resting contact (exists for more than one time step)
bool mIsRestingContact;
// Two orthogonal vectors that span the tangential friction plane
/// Two orthogonal vectors that span the tangential friction plane
std::vector<Vector3> mFrictionVectors;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
ContactPoint(const ContactPoint& contact);
// Private assignment operator
/// Private assignment operator
ContactPoint& operator=(const ContactPoint& contact);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
ContactPoint(RigidBody* const body1, RigidBody* const body2, const ContactInfo* contactInfo);
// Destructor
/// Destructor
virtual ~ContactPoint();
// Return the normal vector of the contact
/// Return the normal vector of the contact
Vector3 getNormal() const;
// Set the penetration depth of the contact
/// Set the penetration depth of the contact
void setPenetrationDepth(decimal penetrationDepth);
// Return the contact local point on body 1
/// Return the contact local point on body 1
Vector3 getLocalPointOnBody1() const;
// Return the contact local point on body 2
/// Return the contact local point on body 2
Vector3 getLocalPointOnBody2() const;
// Return the contact world point on body 1
/// Return the contact world point on body 1
Vector3 getWorldPointOnBody1() const;
// Return the contact world point on body 2
/// Return the contact world point on body 2
Vector3 getWorldPointOnBody2() const;
// Set the contact world point on body 1
/// Set the contact world point on body 1
void setWorldPointOnBody1(const Vector3& worldPoint);
// Set the contact world point on body 2
/// Set the contact world point on body 2
void setWorldPointOnBody2(const Vector3& worldPoint);
// Return true if the contact is a resting contact
/// Return true if the contact is a resting contact
bool getIsRestingContact() const;
// Set the mIsRestingContact variable
/// Set the mIsRestingContact variable
void setIsRestingContact(bool isRestingContact);
// Get the first friction vector
/// Get the first friction vector
Vector3 getFrictionVector1() const;
// Set the first friction vector
/// Set the first friction vector
void setFrictionVector1(const Vector3& frictionVector1);
// Get the second friction vector
/// Get the second friction vector
Vector3 getFrictionVector2() const;
// Set the second friction vector
/// Set the second friction vector
void setFrictionVector2(const Vector3& frictionVector2);
// Return the penetration depth
/// Return the penetration depth
decimal getPenetrationDepth() const;
#ifdef VISUAL_DEBUG
// Draw the contact (for debugging)
/// Draw the contact (for debugging)
void draw() const;
#endif
};

View File

@ -26,7 +26,7 @@
#ifndef DECIMAL_H
#define DECIMAL_H
// ReactPhysiscs3D namespace
/// ReactPhysiscs3D namespace
namespace reactphysics3d {
#if defined(DOUBLE_PRECISION_ENABLED) // If we are compiling for double precision

View File

@ -38,84 +38,83 @@
#include "../constraint/ContactPoint.h"
#include "../memory/MemoryPool.h"
// Namespace reactphysics3d
/// 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
/**
* 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 :
// -------------------- Attributes -------------------- //
// Reference to the collision detection
/// Reference to the collision detection
CollisionDetection mCollisionDetection;
// All the bodies (rigid and soft) of the world
/// All the bodies (rigid and soft) of the world
std::set<CollisionBody*> mBodies;
// Broad-phase overlapping pairs of bodies
/// Broad-phase overlapping pairs of bodies
std::map<bodyindexpair, OverlappingPair*> mOverlappingPairs;
// Current body ID
/// Current body ID
bodyindex mCurrentBodyID;
// Memory pool
/// Memory pool
MemoryPool<CollisionBody> mMemoryPoolCollisionBodies;
// List of free ID for rigid bodies
/// List of free ID for rigid bodies
std::vector<luint> mFreeBodiesIDs;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
CollisionWorld(const CollisionWorld& world);
// Private assignment operator
/// Private assignment operator
CollisionWorld& operator=(const CollisionWorld& world);
// Notify the world about a new broad-phase overlapping pair
/// Notify the world about a new broad-phase overlapping pair
virtual void notifyAddedOverlappingPair(const BroadPhasePair* addedPair);
// Notify the world about a removed broad-phase overlapping pair
/// Notify the world about a removed broad-phase overlapping pair
virtual void notifyRemovedOverlappingPair(const BroadPhasePair* removedPair);
// Notify the world about a new narrow-phase contact
/// Notify the world about a new narrow-phase contact
virtual void notifyNewContact(const BroadPhasePair* pair, const ContactInfo* contactInfo);
// Update the overlapping pair
/// Update the overlapping pair
virtual void updateOverlappingPair(const BroadPhasePair* pair);
// Return the next available body ID
/// Return the next available body ID
bodyindex computeNextAvailableBodyID();
public :
// ----- Methods ----- //
// Constructor
/// Constructor
CollisionWorld();
// Destructor
/// Destructor
virtual ~CollisionWorld();
// Return an iterator to the beginning of the bodies of the physics world
/// Return an iterator to the beginning of the bodies of the physics world
std::set<CollisionBody*>::iterator getBodiesBeginIterator();
// Return an iterator to the end of the bodies of the physics world
/// Return an iterator to the end of the bodies of the physics world
std::set<CollisionBody*>::iterator getBodiesEndIterator();
// Create a collision body
/// Create a collision body
CollisionBody* createCollisionBody(const Transform& transform,
CollisionShape* collisionShape);
// Destroy a collision body
/// Destroy a collision body
void destroyCollisionBody(CollisionBody* collisionBody);
// ----- Friends ----- //

View File

@ -95,11 +95,11 @@ void ContactManifold::removeContactPoint(int index) {
}
// Update the contact manifold
// First the world space coordinates of the current contacts in the manifold are recomputed from
// the corresponding transforms of the bodies because they have moved. Then we remove the contacts
// with a negative penetration depth (meaning that the bodies are not penetrating anymore) and also
// the contacts with a too large distance between the contact points in the plane orthogonal to the
// contact normal
/// First the world space coordinates of the current contacts in the manifold are recomputed from
/// the corresponding transforms of the bodies because they have moved. Then we remove the contacts
/// with a negative penetration depth (meaning that the bodies are not penetrating anymore) and also
/// the contacts with a too large distance between the contact points in the plane orthogonal to the
/// contact normal.
void ContactManifold::update(const Transform& transform1, const Transform& transform2) {
if (mNbContactPoints == 0) return;
@ -140,9 +140,9 @@ void ContactManifold::update(const Transform& transform1, const Transform& trans
}
}
// Return the index of the contact point with the larger penetration depth. This
// corresponding contact will be kept in the cache. The method returns -1 is
// the new contact is the deepest.
// Return the index of the contact point with the larger penetration depth.
/// This corresponding contact will be kept in the cache. The method returns -1 is
/// the new contact is the deepest.
int ContactManifold::getIndexOfDeepestPenetration(ContactPoint* newContact) const {
assert(mNbContactPoints == MAX_CONTACT_POINTS_IN_MANIFOLD);
int indexMaxPenetrationDepth = -1;
@ -162,14 +162,15 @@ int ContactManifold::getIndexOfDeepestPenetration(ContactPoint* newContact) cons
return indexMaxPenetrationDepth;
}
// Return the index that will be removed. The index of the contact point with the larger penetration
// depth is given as a parameter. This contact won't be removed. Given this contact, we compute
// the different area and we want to keep the contacts with the largest area. The new point is also
// kept. In order to compute the area of a quadrilateral, we use the formula :
// Area = 0.5 * | AC x BD | where AC and BD form the diagonals of the quadrilateral. Note that
// when we compute this area, we do not calculate it exactly but we
// only estimate it because we do not compute the actual diagonals of the quadrialteral. Therefore,
// this is only a guess that is faster to compute.
// Return the index that will be removed.
/// The index of the contact point with the larger penetration
/// depth is given as a parameter. This contact won't be removed. Given this contact, we compute
/// the different area and we want to keep the contacts with the largest area. The new point is also
/// kept. In order to compute the area of a quadrilateral, we use the formula :
/// Area = 0.5 * | AC x BD | where AC and BD form the diagonals of the quadrilateral. Note that
/// when we compute this area, we do not calculate it exactly but we
/// only estimate it because we do not compute the actual diagonals of the quadrialteral. Therefore,
/// this is only a guess that is faster to compute.
int ContactManifold::getIndexToRemove(int indexMaxPenetration, const Vector3& newPoint) const {
assert(mNbContactPoints == MAX_CONTACT_POINTS_IN_MANIFOLD);

View File

@ -31,141 +31,140 @@
#include "../body/Body.h"
#include "../constraint/ContactPoint.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Constants
const uint MAX_CONTACT_POINTS_IN_MANIFOLD = 4; // Maximum number of contacts in the manifold
/* -------------------------------------------------------------------
Class ContactManifold :
This class represents the set of contact points between two bodies.
The contact manifold is implemented in a way to cache the contact
points among the frames for better stability following the
"Contact Generation" presentation of Erwin Coumans at GDC 2010
conference (bullet.googlecode.com/files/GDC10_Coumans_Erwin_Contact.pdf).
Some code of this class is based on the implementation of the
btPersistentManifold class from Bullet physics engine (www.http://bulletphysics.org).
The contacts between two bodies are added one after the other in the cache.
When the cache is full, we have to remove one point. The idea is to keep
the point with the deepest penetration depth and also to keep the
points producing the larger area (for a more stable contact manifold).
The new added point is always kept.
-------------------------------------------------------------------
*/
// Class ContactManifold
/**
* This class represents the set of contact points between two bodies.
* The contact manifold is implemented in a way to cache the contact
* points among the frames for better stability following the
* "Contact Generation" presentation of Erwin Coumans at GDC 2010
* conference (bullet.googlecode.com/files/GDC10_Coumans_Erwin_Contact.pdf).
* Some code of this class is based on the implementation of the
* btPersistentManifold class from Bullet physics engine (www.http://bulletphysics.org).
* The contacts between two bodies are added one after the other in the cache.
* When the cache is full, we have to remove one point. The idea is to keep
* the point with the deepest penetration depth and also to keep the
* points producing the larger area (for a more stable contact manifold).
* The new added point is always kept.
*/
class ContactManifold {
private:
// -------------------- Attributes -------------------- //
// Pointer to the first body
/// Pointer to the first body
Body* const mBody1;
// Pointer to the second body
/// Pointer to the second body
Body* const mBody2;
// Contact points in the manifold
/// Contact points in the manifold
ContactPoint* mContactPoints[MAX_CONTACT_POINTS_IN_MANIFOLD];
// Number of contacts in the cache
/// Number of contacts in the cache
uint mNbContactPoints;
// First friction vector of the contact manifold
/// First friction vector of the contact manifold
Vector3 mFrictionVector1;
// Second friction vector of the contact manifold
/// Second friction vector of the contact manifold
Vector3 mFrictionVector2;
// First friction constraint accumulated impulse
/// First friction constraint accumulated impulse
decimal mFrictionImpulse1;
// Second friction constraint accumulated impulse
/// Second friction constraint accumulated impulse
decimal mFrictionImpulse2;
// Twist friction constraint accumulated impulse
/// Twist friction constraint accumulated impulse
decimal mFrictionTwistImpulse;
// Reference to the memory pool with the contacts
/// Reference to the memory pool with the contacts
MemoryPool<ContactPoint>& mMemoryPoolContacts;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
ContactManifold(const ContactManifold& contactManifold);
// Private assignment operator
/// Private assignment operator
ContactManifold& operator=(const ContactManifold& contactManifold);
// Return the index of maximum area
/// Return the index of maximum area
int getMaxArea(decimal area0, decimal area1, decimal area2, decimal area3) const;
// Return the index of the contact with the larger penetration depth
/// Return the index of the contact with the larger penetration depth.
int getIndexOfDeepestPenetration(ContactPoint* newContact) const;
// Return the index that will be removed
/// Return the index that will be removed.
int getIndexToRemove(int indexMaxPenetration, const Vector3& newPoint) const;
// Remove a contact point from the manifold
/// Remove a contact point from the manifold
void removeContactPoint(int index);
// Return true if two vectors are approximatively equal
/// Return true if two vectors are approximatively equal
bool isApproxEqual(const Vector3& vector1, const Vector3& vector2) const;
public:
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
ContactManifold(Body* const mBody1, Body* const mBody2,
MemoryPool<ContactPoint>& mMemoryPoolContacts);
// Destructor
/// Destructor
~ContactManifold();
// Add a contact point to the manifold
/// Add a contact point to the manifold
void addContactPoint(ContactPoint* contact);
// Update the contact manifold
/// Update the contact manifold.
void update(const Transform& transform1, const Transform& transform2);
// Clear the contact manifold
/// Clear the contact manifold
void clear();
// Return the number of contact points in the manifold
/// Return the number of contact points in the manifold
uint getNbContactPoints() const;
// Return the first friction vector at the center of the contact manifold
/// Return the first friction vector at the center of the contact manifold
const Vector3& getFrictionVector1() const;
// set the first friction vector at the center of the contact manifold
/// set the first friction vector at the center of the contact manifold
void setFrictionVector1(const Vector3& mFrictionVector1);
// Return the second friction vector at the center of the contact manifold
/// Return the second friction vector at the center of the contact manifold
const Vector3& getFrictionVector2() const;
// set the second friction vector at the center of the contact manifold
/// set the second friction vector at the center of the contact manifold
void setFrictionVector2(const Vector3& mFrictionVector2);
// Return the first friction accumulated impulse
/// Return the first friction accumulated impulse
decimal getFrictionImpulse1() const;
// Set the first friction accumulated impulse
/// Set the first friction accumulated impulse
void setFrictionImpulse1(decimal frictionImpulse1);
// Return the second friction accumulated impulse
/// Return the second friction accumulated impulse
decimal getFrictionImpulse2() const;
// Set the second friction accumulated impulse
/// Set the second friction accumulated impulse
void setFrictionImpulse2(decimal frictionImpulse2);
// Return the friction twist accumulated impulse
/// Return the friction twist accumulated impulse
decimal getFrictionTwistImpulse() const;
// Set the friction twist accumulated impulse
/// Set the friction twist accumulated impulse
void setFrictionTwistImpulse(decimal frictionTwistImpulse);
// Return a contact point of the manifold
/// Return a contact point of the manifold
ContactPoint* getContactPoint(uint index) const;
};

View File

@ -371,10 +371,10 @@ void ContactSolver::initializeContactConstraints() {
}
}
// Warm start the solver
// For each constraint, we apply the previous impulse (from the previous step)
// at the beginning. With this technique, we will converge faster towards
// the solution of the linear system
// Warm start the solver.
/// For each constraint, we apply the previous impulse (from the previous step)
/// at the beginning. With this technique, we will converge faster towards
/// the solution of the linear system
void ContactSolver::warmStart() {
// For each constraint
@ -836,7 +836,7 @@ void ContactSolver::applySplitImpulse(const Impulse& impulse,
}
// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane
// for a contact point constraint. The two vectors have to be such that : t1 x t2 = contactNormal.
// for a contact point. The two vectors have to be such that : t1 x t2 = contactNormal.
void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity,
ContactPointSolver& contactPoint) const {
@ -866,7 +866,7 @@ void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity,
}
// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane
// for a contact constraint. The two vectors have to be such that : t1 x t2 = contactNormal.
// for a contact manifold. The two vectors have to be such that : t1 x t2 = contactNormal.
void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity,
ContactManifoldSolver& contact) const {

View File

@ -34,22 +34,33 @@
#include <map>
#include <set>
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Declarations
class DynamicsWorld;
// Structure Impulse
/**
* Represents an impulse that we can apply to bodies in the contact or constraint solver.
*/
struct Impulse {
public:
/// Linear impulse applied to the first body
const Vector3 linearImpulseBody1;
/// Linear impulse applied to the second body
const Vector3 linearImpulseBody2;
/// Angular impulse applied to the first body
const Vector3 angularImpulseBody1;
/// Angular impulse applied to the second body
const Vector3 angularImpulseBody2;
// Constructor
/// Constructor
Impulse(const Vector3& linearImpulseBody1, const Vector3& angularImpulseBody1,
const Vector3& linearImpulseBody2, const Vector3& angularImpulseBody2)
: linearImpulseBody1(linearImpulseBody1), angularImpulseBody1(angularImpulseBody1),
@ -59,270 +70,380 @@ struct Impulse {
};
/* -------------------------------------------------------------------
Class ContactSolver :
This class represents the contact solver that is used is solve rigid bodies contacts.
The constraint solver is based on the "Sequential Impulse" technique described by
Erin Catto in his GDC slides (http://code.google.com/p/box2d/downloads/list).
// Class Contact Solver
/**
* This class represents the contact solver that is used to solve rigid bodies contacts.
* The constraint solver is based on the "Sequential Impulse" technique described by
* Erin Catto in his GDC slides (http://code.google.com/p/box2d/downloads/list).
*
* A constraint between two bodies is represented by a function C(x) which is equal to zero
* when the constraint is satisfied. The condition C(x)=0 describes a valid position and the
* condition dC(x)/dt=0 describes a valid velocity. We have dC(x)/dt = Jv + b = 0 where J is
* the Jacobian matrix of the constraint, v is a vector that contains the velocity of both
* bodies and b is the constraint bias. We are looking for a force F_c that will act on the
* bodies to keep the constraint satisfied. Note that from the virtual work principle, we have
* F_c = J^t * lambda where J^t is the transpose of the Jacobian matrix and lambda is a
* Lagrange multiplier. Therefore, finding the force F_c is equivalent to finding the Lagrange
* multiplier lambda.
A constraint between two bodies is represented by a function C(x) which is equal to zero
when the constraint is satisfied. The condition C(x)=0 describes a valid position and the
condition dC(x)/dt=0 describes a valid velocity. We have dC(x)/dt = Jv + b = 0 where J is
the Jacobian matrix of the constraint, v is a vector that contains the velocity of both
bodies and b is the constraint bias. We are looking for a force F_c that will act on the
bodies to keep the constraint satisfied. Note that from the virtual work principle, we have
F_c = J^t * lambda where J^t is the transpose of the Jacobian matrix and lambda is a
Lagrange multiplier. Therefore, finding the force F_c is equivalent to finding the Lagrange
multiplier lambda.
An impulse P = F * dt where F is a force and dt is the timestep. We can apply impulses a
body to change its velocity. The idea of the Sequential Impulse technique is to apply
impulses to bodies of each constraints in order to keep the constraint satisfied.
--- Step 1 ---
First, we integrate the applied force F_a acting of each rigid body (like gravity, ...) and
we obtain some new velocities v2' that tends to violate the constraints.
v2' = v1 + dt * M^-1 * F_a
where M is a matrix that contains mass and inertia tensor information.
--- Step 2 ---
During the second step, we iterate over all the constraints for a certain number of
iterations and for each constraint we compute the impulse to apply to the bodies needed
so that the new velocity of the bodies satisfy Jv + b = 0. From the Newton law, we know that
M * deltaV = P_c where M is the mass of the body, deltaV is the difference of velocity and
P_c is the constraint impulse to apply to the body. Therefore, we have
v2 = v2' + M^-1 * P_c. For each constraint, we can compute the Lagrange multiplier lambda
using : lambda = -m_c (Jv2' + b) where m_c = 1 / (J * M^-1 * J^t). Now that we have the
Lagrange multiplier lambda, we can compute the impulse P_c = J^t * lambda * dt to apply to
the bodies to satisfy the constraint.
--- Step 3 ---
In the third step, we integrate the new position x2 of the bodies using the new velocities
v2 computed in the second step with : x2 = x1 + dt * v2.
Note that in the following code (as it is also explained in the slides from Erin Catto),
the value lambda is not only the lagrange multiplier but is the multiplication of the
Lagrange multiplier with the timestep dt. Therefore, in the following code, when we use
lambda, we mean (lambda * dt).
We are using the accumulated impulse technique that is also described in the slides from
Erin Catto.
We are also using warm starting. The idea is to warm start the solver at the beginning of
each step by applying the last impulstes for the constraints that we already existing at the
previous step. This allows the iterative solver to converge faster towards the solution.
For contact constraints, we are also using split impulses so that the position correction
that uses Baumgarte stabilization does not change the momentum of the bodies.
There are two ways to apply the friction constraints. Either the friction constraints are
applied at each contact point or they are applied only at the center of the contact manifold
between two bodies. If we solve the friction constraints at each contact point, we need
two constraints (two tangential friction directions) and if we solve the friction
constraints at the center of the contact manifold, we need two constraints for tangential
friction but also another twist friction constraint to prevent spin of the body around the
contact manifold center.
-------------------------------------------------------------------
*/
* An impulse P = F * dt where F is a force and dt is the timestep. We can apply impulses a
* body to change its velocity. The idea of the Sequential Impulse technique is to apply
* impulses to bodies of each constraints in order to keep the constraint satisfied.
*
* --- Step 1 ---
*
* First, we integrate the applied force F_a acting of each rigid body (like gravity, ...) and
* we obtain some new velocities v2' that tends to violate the constraints.
*
* v2' = v1 + dt * M^-1 * F_a
*
* where M is a matrix that contains mass and inertia tensor information.
*
* --- Step 2 ---
*
* During the second step, we iterate over all the constraints for a certain number of
* iterations and for each constraint we compute the impulse to apply to the bodies needed
* so that the new velocity of the bodies satisfy Jv + b = 0. From the Newton law, we know that
* M * deltaV = P_c where M is the mass of the body, deltaV is the difference of velocity and
* P_c is the constraint impulse to apply to the body. Therefore, we have
* v2 = v2' + M^-1 * P_c. For each constraint, we can compute the Lagrange multiplier lambda
* using : lambda = -m_c (Jv2' + b) where m_c = 1 / (J * M^-1 * J^t). Now that we have the
* Lagrange multiplier lambda, we can compute the impulse P_c = J^t * lambda * dt to apply to
* the bodies to satisfy the constraint.
*
* --- Step 3 ---
*
* In the third step, we integrate the new position x2 of the bodies using the new velocities
* v2 computed in the second step with : x2 = x1 + dt * v2.
*
* Note that in the following code (as it is also explained in the slides from Erin Catto),
* the value lambda is not only the lagrange multiplier but is the multiplication of the
* Lagrange multiplier with the timestep dt. Therefore, in the following code, when we use
* lambda, we mean (lambda * dt).
*
* We are using the accumulated impulse technique that is also described in the slides from
* Erin Catto.
*
* We are also using warm starting. The idea is to warm start the solver at the beginning of
* each step by applying the last impulstes for the constraints that we already existing at the
* previous step. This allows the iterative solver to converge faster towards the solution.
*
* For contact constraints, we are also using split impulses so that the position correction
* that uses Baumgarte stabilization does not change the momentum of the bodies.
*
* There are two ways to apply the friction constraints. Either the friction constraints are
* applied at each contact point or they are applied only at the center of the contact manifold
* between two bodies. If we solve the friction constraints at each contact point, we need
* two constraints (two tangential friction directions) and if we solve the friction
* constraints at the center of the contact manifold, we need two constraints for tangential
* friction but also another twist friction constraint to prevent spin of the body around the
* contact manifold center.
*/
class ContactSolver {
private:
// Structure ContactPointSolver
// Contact solver internal data structure that to store all the
// information relative to a contact point
/**
* Contact solver internal data structure that to store all the
* information relative to a contact point
*/
struct ContactPointSolver {
decimal penetrationImpulse; // Accumulated normal impulse
decimal friction1Impulse; // Accumulated impulse in the 1st friction direction
decimal friction2Impulse; // Accumulated impulse in the 2nd friction direction
decimal penetrationSplitImpulse; // Accumulated split impulse for penetration correction
Vector3 normal; // Normal vector of the contact
Vector3 frictionVector1; // First friction vector in the tangent plane
Vector3 frictionVector2; // Second friction vector in the tangent plane
Vector3 oldFrictionVector1; // Old first friction vector in the tangent plane
Vector3 oldFrictionVector2; // Old second friction vector in the tangent plane
Vector3 r1; // Vector from the body 1 center to the contact point
Vector3 r2; // Vector from the body 2 center to the contact point
Vector3 r1CrossT1; // Cross product of r1 with 1st friction vector
Vector3 r1CrossT2; // Cross product of r1 with 2nd friction vector
Vector3 r2CrossT1; // Cross product of r2 with 1st friction vector
Vector3 r2CrossT2; // Cross product of r2 with 2nd friction vector
Vector3 r1CrossN; // Cross product of r1 with the contact normal
Vector3 r2CrossN; // Cross product of r2 with the contact normal
decimal penetrationDepth; // Penetration depth
decimal restitutionBias; // Velocity restitution bias
decimal inversePenetrationMass; // Inverse of the matrix K for the penenetration
decimal inverseFriction1Mass; // Inverse of the matrix K for the 1st friction
decimal inverseFriction2Mass; // Inverse of the matrix K for the 2nd friction
bool isRestingContact; // True if the contact was existing last time step
ContactPoint* externalContact; // Pointer to the external contact
/// Accumulated normal impulse
decimal penetrationImpulse;
/// Accumulated impulse in the 1st friction direction
decimal friction1Impulse;
/// Accumulated impulse in the 2nd friction direction
decimal friction2Impulse;
/// Accumulated split impulse for penetration correction
decimal penetrationSplitImpulse;
/// Normal vector of the contact
Vector3 normal;
/// First friction vector in the tangent plane
Vector3 frictionVector1;
/// Second friction vector in the tangent plane
Vector3 frictionVector2;
/// Old first friction vector in the tangent plane
Vector3 oldFrictionVector1;
/// Old second friction vector in the tangent plane
Vector3 oldFrictionVector2;
/// Vector from the body 1 center to the contact point
Vector3 r1;
/// Vector from the body 2 center to the contact point
Vector3 r2;
/// Cross product of r1 with 1st friction vector
Vector3 r1CrossT1;
/// Cross product of r1 with 2nd friction vector
Vector3 r1CrossT2;
/// Cross product of r2 with 1st friction vector
Vector3 r2CrossT1;
/// Cross product of r2 with 2nd friction vector
Vector3 r2CrossT2;
/// Cross product of r1 with the contact normal
Vector3 r1CrossN;
/// Cross product of r2 with the contact normal
Vector3 r2CrossN;
/// Penetration depth
decimal penetrationDepth;
/// Velocity restitution bias
decimal restitutionBias;
/// Inverse of the matrix K for the penenetration
decimal inversePenetrationMass;
/// Inverse of the matrix K for the 1st friction
decimal inverseFriction1Mass;
/// Inverse of the matrix K for the 2nd friction
decimal inverseFriction2Mass;
/// True if the contact was existing last time step
bool isRestingContact;
/// Pointer to the external contact
ContactPoint* externalContact;
};
// Structure ContactManifoldSolver
// Contact solver internal data structure to store all the
// information relative to a contact manifold
/**
* Contact solver internal data structure to store all the
* information relative to a contact manifold.
*/
struct ContactManifoldSolver {
uint indexBody1; // Index of body 1 in the constraint solver
uint indexBody2; // Index of body 2 in the constraint solver
decimal massInverseBody1; // Inverse of the mass of body 1
decimal massInverseBody2; // Inverse of the mass of body 2
Matrix3x3 inverseInertiaTensorBody1; // Inverse inertia tensor of body 1
Matrix3x3 inverseInertiaTensorBody2; // Inverse inertia tensor of body 2
bool isBody1Moving; // True if the body 1 is allowed to move
bool isBody2Moving; // True if the body 2 is allowed to move
ContactPointSolver contacts[MAX_CONTACT_POINTS_IN_MANIFOLD];// Contact point constraints
uint nbContacts; // Number of contact points
decimal restitutionFactor; // Mix of the restitution factor for two bodies
decimal frictionCoefficient; // Mix friction coefficient for the two bodies
ContactManifold* externalContactManifold; // Pointer to the external contact manifold
/// Index of body 1 in the constraint solver
uint indexBody1;
// Variables used when friction constraints are apply at the center of the manifold //
/// Index of body 2 in the constraint solver
uint indexBody2;
Vector3 normal; // Average normal vector of the contact manifold
Vector3 frictionPointBody1; // Point on body 1 where to apply the friction constraints
Vector3 frictionPointBody2; // Point on body 2 where to apply the friction constraints
Vector3 r1Friction; // R1 vector for the friction constraints
Vector3 r2Friction; // R2 vector for the friction constraints
Vector3 r1CrossT1; // Cross product of r1 with 1st friction vector
Vector3 r1CrossT2; // Cross product of r1 with 2nd friction vector
Vector3 r2CrossT1; // Cross product of r2 with 1st friction vector
Vector3 r2CrossT2; // Cross product of r2 with 2nd friction vector
decimal inverseFriction1Mass; // Matrix K for the first friction constraint
decimal inverseFriction2Mass; // Matrix K for the second friction constraint
decimal inverseTwistFrictionMass; // Matrix K for the twist friction constraint
Vector3 frictionVector1; // First friction direction at contact manifold center
Vector3 frictionVector2; // Second friction direction at contact manifold center
Vector3 oldFrictionVector1; // Old 1st friction direction at contact manifold center
Vector3 oldFrictionVector2; // Old 2nd friction direction at contact manifold center
decimal friction1Impulse; // First friction direction impulse at manifold center
decimal friction2Impulse; // Second friction direction impulse at manifold center
decimal frictionTwistImpulse; // Twist friction impulse at contact manifold center
/// Inverse of the mass of body 1
decimal massInverseBody1;
// Inverse of the mass of body 2
decimal massInverseBody2;
/// Inverse inertia tensor of body 1
Matrix3x3 inverseInertiaTensorBody1;
/// Inverse inertia tensor of body 2
Matrix3x3 inverseInertiaTensorBody2;
/// True if the body 1 is allowed to move
bool isBody1Moving;
/// True if the body 2 is allowed to move
bool isBody2Moving;
/// Contact point constraints
ContactPointSolver contacts[MAX_CONTACT_POINTS_IN_MANIFOLD];
/// Number of contact points
uint nbContacts;
/// Mix of the restitution factor for two bodies
decimal restitutionFactor;
/// Mix friction coefficient for the two bodies
decimal frictionCoefficient;
/// Pointer to the external contact manifold
ContactManifold* externalContactManifold;
// - Variables used when friction constraints are apply at the center of the manifold-//
/// Average normal vector of the contact manifold
Vector3 normal;
/// Point on body 1 where to apply the friction constraints
Vector3 frictionPointBody1;
/// Point on body 2 where to apply the friction constraints
Vector3 frictionPointBody2;
/// R1 vector for the friction constraints
Vector3 r1Friction;
/// R2 vector for the friction constraints
Vector3 r2Friction;
/// Cross product of r1 with 1st friction vector
Vector3 r1CrossT1;
/// Cross product of r1 with 2nd friction vector
Vector3 r1CrossT2;
/// Cross product of r2 with 1st friction vector
Vector3 r2CrossT1;
/// Cross product of r2 with 2nd friction vector
Vector3 r2CrossT2;
/// Matrix K for the first friction constraint
decimal inverseFriction1Mass;
/// Matrix K for the second friction constraint
decimal inverseFriction2Mass;
/// Matrix K for the twist friction constraint
decimal inverseTwistFrictionMass;
/// First friction direction at contact manifold center
Vector3 frictionVector1;
/// Second friction direction at contact manifold center
Vector3 frictionVector2;
/// Old 1st friction direction at contact manifold center
Vector3 oldFrictionVector1;
/// Old 2nd friction direction at contact manifold center
Vector3 oldFrictionVector2;
/// First friction direction impulse at manifold center
decimal friction1Impulse;
/// Second friction direction impulse at manifold center
decimal friction2Impulse;
/// Twist friction impulse at contact manifold center
decimal frictionTwistImpulse;
};
// -------------------- Constants --------------------- //
// Beta value for the penetration depth position correction without split impulses
/// Beta value for the penetration depth position correction without split impulses
static const decimal BETA;
// Beta value for the penetration depth position correction with split impulses
/// Beta value for the penetration depth position correction with split impulses
static const decimal BETA_SPLIT_IMPULSE;
// Slop distance (allowed penetration distance between bodies)
/// Slop distance (allowed penetration distance between bodies)
static const decimal SLOP;
// -------------------- Attributes -------------------- //
// Reference to the world
/// Reference to the world
DynamicsWorld& mWorld;
// Number of iterations of the constraints solver
/// Number of iterations of the constraints solver
uint mNbIterations;
// Split linear velocities for the position contact solver (split impulse)
/// Split linear velocities for the position contact solver (split impulse)
Vector3* mSplitLinearVelocities;
// Split angular velocities for the position contact solver (split impulse)
/// Split angular velocities for the position contact solver (split impulse)
Vector3* mSplitAngularVelocities;
// Current time step
/// Current time step
decimal mTimeStep;
// Contact constraints
/// Contact constraints
ContactManifoldSolver* mContactConstraints;
// Number of contact constraints
/// Number of contact constraints
uint mNbContactManifolds;
// Constrained bodies
/// Constrained bodies
std::set<RigidBody*> mConstraintBodies;
// Pointer to the array of constrained linear velocities (state of the linear velocities
// after solving the constraints)
/// Pointer to the array of constrained linear velocities (state of the linear velocities
/// after solving the constraints)
std::vector<Vector3>& mConstrainedLinearVelocities;
// Pointer to the array of constrained angular velocities (state of the angular velocities
// after solving the constraints)
/// Pointer to the array of constrained angular velocities (state of the angular velocities
/// after solving the constraints)
std::vector<Vector3>& mConstrainedAngularVelocities;
// Reference to the map of rigid body to their index in the constrained velocities array
/// Reference to the map of rigid body to their index in the constrained velocities array
const std::map<RigidBody*, uint>& mMapBodyToConstrainedVelocityIndex;
// True if the warm starting of the solver is active
/// True if the warm starting of the solver is active
bool mIsWarmStartingActive;
// True if the split impulse position correction is active
/// True if the split impulse position correction is active
bool mIsSplitImpulseActive;
// True if we solve 3 friction constraints at the contact manifold center only
// instead of 2 friction constraints at each contact point
/// True if we solve 3 friction constraints at the contact manifold center only
/// instead of 2 friction constraints at each contact point
bool mIsSolveFrictionAtContactManifoldCenterActive;
// -------------------- Methods -------------------- //
// Initialize the constraint solver
/// Initialize the constraint solver
void initialize();
// Initialize the split impulse velocities
/// Initialize the split impulse velocities
void initializeSplitImpulseVelocities();
// Initialize the contact constraints before solving the system
/// Initialize the contact constraints before solving the system
void initializeContactConstraints();
// Store the computed impulses to use them to
// warm start the solver at the next iteration
/// Store the computed impulses to use them to
/// warm start the solver at the next iteration
void storeImpulses();
// Warm start the solver
/// Warm start the solver.
void warmStart();
// Solve the contact constraints by applying sequential impulses
/// Solve the contact constraints by applying sequential impulses
void solveContactConstraints();
// Apply an impulse to the two bodies of a constraint
/// Apply an impulse to the two bodies of a constraint
void applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold);
// Apply an impulse to the two bodies of a constraint
/// Apply an impulse to the two bodies of a constraint
void applySplitImpulse(const Impulse& impulse,
const ContactManifoldSolver& manifold);
// Compute the collision restitution factor from the restitution factor of each body
/// Compute the collision restitution factor from the restitution factor of each body
decimal computeMixedRestitutionFactor(const RigidBody* body1,
const RigidBody* body2) const;
// Compute the mixed friction coefficient from the friction coefficient of each body
/// Compute the mixed friction coefficient from the friction coefficient of each body
decimal computeMixedFrictionCoefficient(const RigidBody* body1,
const RigidBody* body2)const;
// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction
// plane for a contact point constraint. The two vectors have to be
// such that : t1 x t2 = contactNormal.
/// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction
/// plane for a contact point. The two vectors have to be
/// such that : t1 x t2 = contactNormal.
void computeFrictionVectors(const Vector3& deltaVelocity,
ContactPointSolver &contactPoint) const;
// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction
// plane for a contact constraint. The two vectors have to be
// such that : t1 x t2 = contactNormal.
/// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction
/// plane for a contact manifold. The two vectors have to be
/// such that : t1 x t2 = contactNormal.
void computeFrictionVectors(const Vector3& deltaVelocity,
ContactManifoldSolver& contactPoint) const;
// Compute a penetration constraint impulse
/// Compute a penetration constraint impulse
const Impulse computePenetrationImpulse(decimal deltaLambda,
const ContactPointSolver& contactPoint) const;
// Compute the first friction constraint impulse
/// Compute the first friction constraint impulse
const Impulse computeFriction1Impulse(decimal deltaLambda,
const ContactPointSolver& contactPoint) const;
// Compute the second friction constraint impulse
/// Compute the second friction constraint impulse
const Impulse computeFriction2Impulse(decimal deltaLambda,
const ContactPointSolver& contactPoint) const;
@ -330,43 +451,43 @@ class ContactSolver {
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
ContactSolver(DynamicsWorld& mWorld, std::vector<Vector3>& constrainedLinearVelocities,
std::vector<Vector3>& constrainedAngularVelocities,
const std::map<RigidBody*, uint>& mapBodyToVelocityIndex);
// Destructor
/// Destructor
virtual ~ContactSolver();
// Solve the constraints
/// Solve the constraints
void solve(decimal timeStep);
// Return true if the body is in at least one constraint
/// Return true if the body is in at least one constraint
bool isConstrainedBody(RigidBody* body) const;
// Return the constrained linear velocity of a body after solving the constraints
/// Return the constrained linear velocity of a body after solving the constraints
Vector3 getConstrainedLinearVelocityOfBody(RigidBody *body);
// Return the split linear velocity
/// Return the split linear velocity
Vector3 getSplitLinearVelocityOfBody(RigidBody* body);
// Return the constrained angular velocity of a body after solving the constraints
/// Return the constrained angular velocity of a body after solving the constraints
Vector3 getConstrainedAngularVelocityOfBody(RigidBody* body);
// Return the split angular velocity
/// Return the split angular velocity
Vector3 getSplitAngularVelocityOfBody(RigidBody* body);
// Clean up the constraint solver
/// Clean up the constraint solver
void cleanup();
// Set the number of iterations of the constraint solver
/// Set the number of iterations of the constraint solver
void setNbIterationsSolver(uint nbIterations);
// Activate or Deactivate the split impulses for contacts
/// Activate or Deactivate the split impulses for contacts
void setIsSplitImpulseActive(bool isActive);
// Activate or deactivate the solving of friction constraints at the center of
// the contact manifold instead of solving them at each contact point
/// Activate or deactivate the solving of friction constraints at the center of
/// the contact manifold instead of solving them at each contact point
void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive);
};

View File

@ -34,188 +34,187 @@
#include "Timer.h"
#include "../configuration.h"
// Namespace ReactPhysics3D
/// Namespace ReactPhysics3D
namespace reactphysics3d {
/* -------------------------------------------------------------------
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 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 DynamicsWorld : public CollisionWorld {
protected :
// -------------------- Attributes -------------------- //
// Timer of the physics engine
/// Timer of the physics engine
Timer mTimer;
// Contact solver
/// Contact solver
ContactSolver mContactSolver;
// True if the deactivation (sleeping) of inactive bodies is enabled
/// True if the deactivation (sleeping) of inactive bodies is enabled
bool mIsDeactivationActive;
// All the rigid bodies of the physics world
/// All the rigid bodies of the physics world
std::set<RigidBody*> mRigidBodies;
// All the contact constraints
/// All the contact constraints
std::vector<ContactManifold*> mContactManifolds;
// All the constraints (except contact constraints)
/// All the constraints (except contact constraints)
std::vector<Constraint*> mConstraints;
// Gravity vector of the world
/// Gravity vector of the world
Vector3 mGravity;
// True if the gravity force is on
/// True if the gravity force is on
bool mIsGravityOn;
// Memory pool for the overlapping pairs
/// Memory pool for the overlapping pairs
MemoryPool<OverlappingPair> mMemoryPoolOverlappingPairs;
// Memory pool for rigid bodies memory allocation
/// Memory pool for rigid bodies memory allocation
MemoryPool<RigidBody> mMemoryPoolRigidBodies;
// Memory pool for the contacts
/// Memory pool for the contacts
MemoryPool<ContactPoint> mMemoryPoolContacts;
// Array of constrained linear velocities (state of the linear velocities
// after solving the constraints)
/// Array of constrained linear velocities (state of the linear velocities
/// after solving the constraints)
std::vector<Vector3> mConstrainedLinearVelocities;
// Array of constrained angular velocities (state of the angular velocities
// after solving the constraints)
/// Array of constrained angular velocities (state of the angular velocities
/// after solving the constraints)
std::vector<Vector3> mConstrainedAngularVelocities;
// Map body to their index in the constrained velocities array
/// Map body to their index in the constrained velocities array
std::map<RigidBody*, uint> mMapBodyToConstrainedVelocityIndex;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
DynamicsWorld(const DynamicsWorld& world);
// Private assignment operator
/// Private assignment operator
DynamicsWorld& operator=(const DynamicsWorld& world);
// Compute the motion of all bodies and update their positions and orientations
/// Compute the motion of all bodies and update their positions and orientations
void updateRigidBodiesPositionAndOrientation();
// Update the position and orientation of a body
/// Update the position and orientation of a body
void updatePositionAndOrientationOfBody(RigidBody* body, Vector3 newLinVelocity,
Vector3 newAngVelocity);
// Compute and set the interpolation factor to all bodies
/// Compute and set the interpolation factor to all bodies
void setInterpolationFactorToAllBodies();
// Initialize the constrained velocities array at each step
/// Initialize the constrained velocities array at each step
void initConstrainedVelocitiesArray();
// Cleanup the constrained velocities array at each step
/// Cleanup the constrained velocities array at each step
void cleanupConstrainedVelocitiesArray();
// Apply the gravity force to all bodies
/// Apply the gravity force to all bodies
void applyGravity();
// Reset the boolean movement variable of each body
/// Reset the boolean movement variable of each body
void resetBodiesMovementVariable();
// Update the overlapping pair
/// Update the overlapping pair
virtual void updateOverlappingPair(const BroadPhasePair* pair);
// Notify the world about a new broad-phase overlapping pair
/// Notify the world about a new broad-phase overlapping pair
virtual void notifyAddedOverlappingPair(const BroadPhasePair* addedPair);
// Notify the world about a removed broad-phase overlapping pair
/// Notify the world about a removed broad-phase overlapping pair
virtual void notifyRemovedOverlappingPair(const BroadPhasePair* removedPair);
// Notify the world about a new narrow-phase contact
/// Notify the world about a new narrow-phase contact
virtual void notifyNewContact(const BroadPhasePair* pair, const ContactInfo* contactInfo);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
DynamicsWorld(const Vector3& mGravity, decimal timeStep);
// Destructor
/// Destructor
virtual ~DynamicsWorld();
// Start the physics simulation
/// Start the physics simulation
void start();
// Stop the physics simulation
/// Stop the physics simulation
void stop();
// Update the physics simulation
/// Update the physics simulation
void update();
// Set the number of iterations of the constraint solver
/// Set the number of iterations of the constraint solver
void setNbIterationsSolver(uint nbIterations);
// Activate or Deactivate the split impulses for contacts
/// Activate or Deactivate the split impulses for contacts
void setIsSplitImpulseActive(bool isActive);
// Activate or deactivate the solving of friction constraints at the center of
// the contact manifold instead of solving them at each contact point
/// Activate or deactivate the solving of friction constraints at the center of
/// the contact manifold instead of solving them at each contact point
void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive);
// Set the isErrorCorrectionActive value
/// Set the isErrorCorrectionActive value
void setIsErrorCorrectionActive(bool isErrorCorrectionActive);
// Create a rigid body into the physics world
/// Create a rigid body into the physics world
RigidBody* createRigidBody(const Transform& transform, decimal mass,
const Matrix3x3& inertiaTensorLocal,
CollisionShape* collisionShape);
// Destroy a rigid body
/// Destroy a rigid body
void destroyRigidBody(RigidBody* rigidBody);
// Return the gravity vector of the world
/// Return the gravity vector of the world
Vector3 getGravity() const;
// Return if the gravity is on
/// Return if the gravity is on
bool getIsGravityOn() const;
// Set the isGravityOn attribute
/// Set the isGravityOn attribute
void setIsGratityOn(bool isGravityOn);
// Return the number of rigid bodies in the world
/// Return the number of rigid bodies in the world
uint getNbRigidBodies() const;
// Add a constraint
/// Add a constraint
void addConstraint(Constraint* constraint);
// Remove a constraint
/// Remove a constraint
void removeConstraint(Constraint* constraint);
// Remove all constraints and delete them (free their memory)
/// Remove all constraints and delete them (free their memory)
void removeAllConstraints();
// Return the number of contact constraints in the world
/// Return the number of contact constraints in the world
uint getNbContactManifolds() const;
// Return a start iterator on the constraint list
/// Return a start iterator on the constraint list
std::vector<Constraint*>::iterator getConstraintsBeginIterator();
// Return a end iterator on the constraint list
/// Return a end iterator on the constraint list
std::vector<Constraint*>::iterator getConstraintsEndIterator();
// Return a start iterator on the contact manifolds list
/// Return a start iterator on the contact manifolds list
std::vector<ContactManifold*>::iterator getContactManifoldsBeginIterator();
// Return a end iterator on the contact manifolds list
/// Return a end iterator on the contact manifolds list
std::vector<ContactManifold*>::iterator getContactManifoldsEndIterator();
// Return an iterator to the beginning of the rigid bodies of the physics world
/// Return an iterator to the beginning of the rigid bodies of the physics world
std::set<RigidBody*>::iterator getRigidBodiesBeginIterator();
// Return an iterator to the end of the rigid bodies of the physics world
/// Return an iterator to the end of the rigid bodies of the physics world
std::set<RigidBody*>::iterator getRigidBodiesEndIterator();
};

View File

@ -29,77 +29,76 @@
// Libraries
#include "ContactManifold.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class OverlappingPair :
This class represents a pair of two bodies that are overlapping
during the broad-phase collision detection. It is created when
the two bodies start to overlap and is destroy when they do not
overlap anymore. This class contains the cache with all the
current contacts between the bodies.
-------------------------------------------------------------------
*/
// Class OverlappingPair
/**
* This class represents a pair of two bodies that are overlapping
* during the broad-phase collision detection. It is created when
* the two bodies start to overlap and is destroyed when they do not
* overlap anymore. This class contains a contact manifold that
* store all the contact points between the two bodies.
*/
class OverlappingPair {
private:
// -------------------- Attributes -------------------- //
// Pointer to the first body of the contact
/// Pointer to the first body of the contact
CollisionBody* const mBody1;
// Pointer to the second body of the contact
/// Pointer to the second body of the contact
CollisionBody* const mBody2;
// Persistent contact manifold
/// Persistent contact manifold
ContactManifold mContactManifold;
// Cached previous separating axis
/// Cached previous separating axis
Vector3 mCachedSeparatingAxis;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
OverlappingPair(const OverlappingPair& pair);
// Private assignment operator
/// Private assignment operator
OverlappingPair& operator=(const OverlappingPair& pair);
public:
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
OverlappingPair(CollisionBody* body1, CollisionBody* body2,
MemoryPool<ContactPoint>& memoryPoolContacts);
// Destructor
/// Destructor
~OverlappingPair();
// Return the pointer to first body
/// Return the pointer to first body
CollisionBody* const getBody1() const;
// Return the pointer to second body
/// Return the pointer to second body
CollisionBody* const getBody2() const;
// Add a contact to the contact cache
/// Add a contact to the contact cache
void addContact(ContactPoint* contact);
// Update the contact cache
/// Update the contact cache
void update();
// Return the cached separating axis
/// Return the cached separating axis
Vector3 getCachedSeparatingAxis() const;
// Set the cached separating axis
/// Set the cached separating axis
void setCachedSeparatingAxis(const Vector3& axis);
// Return the number of contacts in the cache
/// Return the number of contacts in the cache
uint getNbContactPoints() const;
// Return the contact manifold
/// Return the contact manifold
ContactManifold* getContactManifold();
};

View File

@ -40,86 +40,85 @@
#endif
// Namespace ReactPhysics3D
/// Namespace ReactPhysics3D
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class Timer :
This class will take care of the time in the physics engine. It
uses fuunctions that depend on the current platform to get the
current time.
-------------------------------------------------------------------
*/
// Class Timer
/**
* This class will take care of the time in the physics engine. It
* uses fuunctions that depend on the current platform to get the
* current time.
*/
class Timer {
private :
// -------------------- Attributes -------------------- //
// Timestep dt of the physics engine (timestep > 0.0)
/// Timestep dt of the physics engine (timestep > 0.0)
double mTimeStep;
// Current time of the physics engine
/// Current time of the physics engine
long double mTime;
// Last time the timer has been updated
/// Last time the timer has been updated
long double mLastUpdateTime;
// Time difference between the two last timer update() calls
/// Time difference between the two last timer update() calls
long double mDeltaTime;
// Used to fix the time step and avoid strange time effects
/// Used to fix the time step and avoid strange time effects
double mAccumulator;
// True if the timer is running
/// True if the timer is running
bool mIsRunning;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
Timer(const Timer& timer);
// Private assignment operator
/// Private assignment operator
Timer& operator=(const Timer& timer);
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
Timer(double timeStep);
// Destructor
/// Destructor
virtual ~Timer();
// Return the timestep of the physics engine
/// Return the timestep of the physics engine
double getTimeStep() const;
// Set the timestep of the physics engine
/// Set the timestep of the physics engine
void setTimeStep(double timeStep);
// Return the current time
/// Return the current time
long double getTime() const;
// Start the timer
/// Start the timer
void start();
// Stop the timer
/// Stop the timer
void stop();
// Return true if the timer is running
/// Return true if the timer is running
bool getIsRunning() const;
// True if it's possible to take a new step
/// True if it's possible to take a new step
bool isPossibleToTakeStep() const;
// Compute the time since the last update() call and add it to the accumulator
/// Compute the time since the last update() call and add it to the accumulator
void update();
// Take a new step => update the timer by adding the timeStep value to the current time
/// Take a new step => update the timer by adding the timeStep value to the current time
void nextStep();
// Compute the interpolation factor
/// Compute the interpolation factor
double computeInterpolationFactor();
};

View File

@ -31,115 +31,114 @@
#include <cassert>
#include "Vector3.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class Matrix3x3 :
This class represents a 3x3 matrix.
-------------------------------------------------------------------
*/
// Class Matrix3x3
/**
* This class represents a 3x3 matrix.
*/
class Matrix3x3 {
private :
// -------------------- Attributes -------------------- //
// Array with the values of the matrix
/// Array with the values of the matrix
decimal mArray[3][3];
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
Matrix3x3();
// Constructor
/// Constructor
Matrix3x3(decimal value);
// Constructor
/// Constructor
Matrix3x3(decimal a1, decimal a2, decimal a3, decimal b1, decimal b2, decimal b3,
decimal c1, decimal c2, decimal c3);
// Destructor
/// Destructor
virtual ~Matrix3x3();
// Copy-constructor
/// Copy-constructor
Matrix3x3(const Matrix3x3& matrix);
// Assignment operator
/// Assignment operator
Matrix3x3& operator=(const Matrix3x3& matrix);
// Get a value in the matrix
/// Get a value in the matrix
decimal getValue(int i, int j) const;
// Set a value in the matrix
/// Set a value in the matrix
void setValue(int i, int j, decimal value);
// Set all the values in the matrix
/// Set all the values in the matrix
void setAllValues(decimal a1, decimal a2, decimal a3, decimal b1, decimal b2, decimal b3,
decimal c1, decimal c2, decimal c3);
// Return a column
/// Return a column
Vector3 getColumn(int i) const;
// Return the transpose matrix
/// Return the transpose matrix
Matrix3x3 getTranspose() const;
// Return the determinant of the matrix
/// Return the determinant of the matrix
decimal getDeterminant() const;
// Return the trace of the matrix
/// Return the trace of the matrix
decimal getTrace() const;
// Return the inverse matrix
/// Return the inverse matrix
Matrix3x3 getInverse() const;
// Return the matrix with absolute values
/// Return the matrix with absolute values
Matrix3x3 getAbsoluteMatrix() const;
// Set the matrix to the identity matrix
/// Set the matrix to the identity matrix
void setToIdentity();
// Return the 3x3 identity matrix
/// Return the 3x3 identity matrix
static Matrix3x3 identity();
// Overloaded operator for addition
/// Overloaded operator for addition
friend Matrix3x3 operator+(const Matrix3x3& matrix1, const Matrix3x3& matrix2);
// Overloaded operator for substraction
/// Overloaded operator for substraction
friend Matrix3x3 operator-(const Matrix3x3& matrix1, const Matrix3x3& matrix2);
// Overloaded operator for the negative of the matrix
/// Overloaded operator for the negative of the matrix
friend Matrix3x3 operator-(const Matrix3x3& matrix);
// Overloaded operator for multiplication with a number
/// Overloaded operator for multiplication with a number
friend Matrix3x3 operator*(decimal nb, const Matrix3x3& matrix);
// Overloaded operator for multiplication with a matrix
/// Overloaded operator for multiplication with a matrix
friend Matrix3x3 operator*(const Matrix3x3& matrix, decimal nb);
// Overloaded operator for matrix multiplication
/// Overloaded operator for matrix multiplication
friend Matrix3x3 operator*(const Matrix3x3& matrix1, const Matrix3x3& matrix2);
// Overloaded operator for multiplication with a vector
/// Overloaded operator for multiplication with a vector
friend Vector3 operator*(const Matrix3x3& matrix, const Vector3& vector);
// Overloaded operator for equality condition
/// Overloaded operator for equality condition
bool operator==(const Matrix3x3& matrix) const;
// Overloaded operator for the is different condition
/// Overloaded operator for the is different condition
bool operator!= (const Matrix3x3& matrix) const;
// Overloaded operator for addition with assignment
/// Overloaded operator for addition with assignment
Matrix3x3& operator+=(const Matrix3x3& matrix);
// Overloaded operator for substraction with assignment
/// Overloaded operator for substraction with assignment
Matrix3x3& operator-=(const Matrix3x3& matrix);
// Overloaded operator for multiplication with a number with assignment
/// Overloaded operator for multiplication with a number with assignment
Matrix3x3& operator*=(decimal nb);
};

View File

@ -130,9 +130,9 @@ Quaternion::~Quaternion() {
}
// Compute the rotation angle (in radians) and the 3D rotation axis
// This method is used to get the rotation angle (in radian) and the unit
// rotation axis of an orientation quaternion.
// Compute the rotation angle (in radians) and the rotation axis
/// This method is used to get the rotation angle (in radian) and the unit
/// rotation axis of an orientation quaternion.
void Quaternion::getRotationAngleAxis(decimal& angle, Vector3& axis) const {
Quaternion quaternion;
@ -189,7 +189,7 @@ Matrix3x3 Quaternion::getMatrix() const {
}
// Compute the spherical linear interpolation between two quaternions.
// The t argument has to be such that 0 <= t <= 1. This method is static.
/// The t argument has to be such that 0 <= t <= 1. This method is static.
Quaternion Quaternion::slerp(const Quaternion& quaternion1,
const Quaternion& quaternion2, decimal t) {
assert(t >= 0.0 && t <= 1.0);
@ -226,5 +226,3 @@ Quaternion Quaternion::slerp(const Quaternion& quaternion1,
// Compute and return the interpolated quaternion
return quaternion1 * coeff1 + quaternion2 * coeff2;
}

View File

@ -32,91 +32,90 @@
#include "Matrix3x3.h"
#include "../decimal.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class Quaternion :
This class represents a quaternion. We use the notation :
q = (x*i, y*j, z*k, w) to represent a quaternion.
-------------------------------------------------------------------
*/
// Class Quaternion
/**
* This class represents a quaternion. We use the notation :
* q = (x*i, y*j, z*k, w) to represent a quaternion.
*/
struct Quaternion {
public :
// -------------------- Attributes -------------------- //
// Components of the quaternion
/// Components of the quaternion
decimal x, y, z, w;
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
Quaternion();
// Constructor with arguments
/// Constructor with arguments
Quaternion(decimal newX, decimal newY, decimal newZ, decimal newW);
// Constructor with the component w and the vector v=(x y z)
/// Constructor with the component w and the vector v=(x y z)
Quaternion(decimal newW, const Vector3& v);
// Copy-constructor
/// Copy-constructor
Quaternion(const Quaternion& quaternion);
// Create a unit quaternion from a rotation matrix
/// Create a unit quaternion from a rotation matrix
Quaternion(const Matrix3x3& matrix);
// Destructor
/// Destructor
~Quaternion();
// Return the vector v=(x y z) of the quaternion
/// Return the vector v=(x y z) of the quaternion
Vector3 vectorV() const;
// Return the length of the quaternion
/// Return the length of the quaternion
decimal length() const;
// Return the unit quaternion
/// Return the unit quaternion
Quaternion getUnit() const;
// Return the conjugate quaternion
/// Return the conjugate quaternion
Quaternion getConjugate() const;
// Return the inverse of the quaternion
/// Return the inverse of the quaternion
Quaternion getInverse() const;
// Return the orientation matrix corresponding to this quaternion
/// Return the orientation matrix corresponding to this quaternion
Matrix3x3 getMatrix() const;
// Return the identity quaternion
/// Return the identity quaternion
static Quaternion identity();
// Dot product between two quaternions
/// Dot product between two quaternions
decimal dot(const Quaternion& quaternion) const;
// Compute the rotation angle (in radians) and the axis
/// Compute the rotation angle (in radians) and the rotation axis
void getRotationAngleAxis(decimal& angle, Vector3& axis) const;
// Compute the spherical linear interpolation between two quaternions
/// Compute the spherical linear interpolation between two quaternions
static Quaternion slerp(const Quaternion& quaternion1, const Quaternion& quaternion2,
decimal t);
// Overloaded operator for the addition
/// Overloaded operator for the addition
Quaternion operator+(const Quaternion& quaternion) const;
// Overloaded operator for the substraction
/// Overloaded operator for the substraction
Quaternion operator-(const Quaternion& quaternion) const;
// Overloaded operator for the multiplication with a constant
/// Overloaded operator for the multiplication with a constant
Quaternion operator*(decimal nb) const;
// Overloaded operator for the multiplication
/// Overloaded operator for the multiplication
Quaternion operator*(const Quaternion& quaternion) const;
// Overloaded operator for assignment
/// Overloaded operator for assignment
Quaternion& operator=(const Quaternion& quaternion);
// Overloaded operator for equality condition
/// Overloaded operator for equality condition
bool operator==(const Quaternion& quaternion) const;
};

View File

@ -34,85 +34,84 @@
// ReactPhysiscs3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class Transform :
This class represents a position and an orientation in 3D. It can
also be seen as representing a translation and a rotation
-------------------------------------------------------------------
*/
// Class Transform
/**
* This class represents a position and an orientation in 3D. It can
* also be seen as representing a translation and a rotation.
*/
class Transform {
private :
// -------------------- Attributes -------------------- //
// Position
/// Position
Vector3 mPosition;
// Orientation
/// Orientation
Quaternion mOrientation;
public :
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
Transform();
// Constructor
/// Constructor
Transform(const Vector3& position, const Matrix3x3& orientation);
// Constructor
/// Constructor
Transform(const Vector3& position, const Quaternion& orientation);
// Destructor
/// Destructor
~Transform();
// Copy-constructor
/// Copy-constructor
Transform(const Transform& transform);
// Return the origin of the transform
/// Return the origin of the transform
const Vector3& getPosition() const;
// Set the origin of the transform
/// Set the origin of the transform
void setPosition(const Vector3& position);
// Return the orientation quaternion
/// Return the orientation quaternion
const Quaternion& getOrientation() const;
// Set the rotation quaternion
/// Set the rotation quaternion
void setOrientation(const Quaternion& orientation);
// Set the transform to the identity transform
/// Set the transform to the identity transform
void setToIdentity();
// Set the transform from an OpenGL transform matrix
/// Set the transform from an OpenGL transform matrix
void setFromOpenGL(decimal* openglMatrix);
// Get the OpenGL matrix of the transform
/// Get the OpenGL matrix of the transform
void getOpenGLMatrix(decimal* openglMatrix) const;
// Return the inverse of the transform
/// Return the inverse of the transform
Transform inverse() const;
// Return an interpolated transform
/// Return an interpolated transform
static Transform interpolateTransforms(const Transform& oldTransform,
const Transform& newTransform,
decimal interpolationFactor);
// Return the transformed vector
/// Return the transformed vector
Vector3 operator*(const Vector3& vector) const;
// Operator of multiplication of a transform with another one
/// Operator of multiplication of a transform with another one
Transform operator*(const Transform& transform2) const;
// Return true if the two transforms are equal
/// Return true if the two transforms are equal
bool operator==(const Transform& transform2) const;
// Return true if the two transforms are different
/// Return true if the two transforms are different
bool operator!=(const Transform& transform2) const;
// Assignment operator
/// Assignment operator
Transform& operator=(const Transform& transform);
};

View File

@ -33,104 +33,103 @@
#include "../decimal.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Structure Vector3 :
This class represents a 3D vector.
-------------------------------------------------------------------
*/
// Class Vector3
/**
* This class represents a 3D vector.
*/
struct Vector3 {
public:
// -------------------- Attributes -------------------- //
// Values of the 3D vector
/// Values of the 3D vector
decimal x, y, z;
// -------------------- Methods -------------------- //
// Constructor of the class Vector3D
/// Constructor of the class Vector3D
Vector3();
// Constructor with arguments
/// Constructor with arguments
Vector3(decimal newX, decimal newY, decimal newZ);
// Copy-constructor
/// Copy-constructor
Vector3(const Vector3& vector);
// Destructor
/// Destructor
~Vector3();
// Set all the values of the vector
/// Set all the values of the vector
void setAllValues(decimal newX, decimal newY, decimal newZ);
// Return the lenght of the vector
/// Return the lenght of the vector
decimal length() const;
// Return the square of the length of the vector
/// Return the square of the length of the vector
decimal lengthSquare() const;
// Return the corresponding unit vector
/// Return the corresponding unit vector
Vector3 getUnit() const;
// Return one unit orthogonal vector of the current vector
/// Return one unit orthogonal vector of the current vector
Vector3 getOneUnitOrthogonalVector() const;
// Return true if the vector is unit and false otherwise
/// Return true if the vector is unit and false otherwise
bool isUnit() const;
// Return true if the current vector is the zero vector
/// Return true if the current vector is the zero vector
bool isZero() const;
// Dot product of two vectors
/// Dot product of two vectors
decimal dot(const Vector3& vector) const;
// Cross product of two vectors
/// Cross product of two vectors
Vector3 cross(const Vector3& vector) const;
// Normalize the vector
/// Normalize the vector
void normalize();
// Return the corresponding absolute value vector
/// Return the corresponding absolute value vector
Vector3 getAbsoluteVector() const;
// Return the axis with the minimal value
/// Return the axis with the minimal value
int getMinAxis() const;
// Return the axis with the maximal value
/// Return the axis with the maximal value
int getMaxAxis() const;
// Return true if two vectors are parallel
/// Return true if two vectors are parallel
bool isParallelWith(const Vector3& vector) const;
// Overloaded operator for the equality condition
/// Overloaded operator for the equality condition
bool operator== (const Vector3& vector) const;
// Overloaded operator for the is different condition
/// Overloaded operator for the is different condition
bool operator!= (const Vector3& vector) const;
// Overloaded operator for addition with assignment
/// Overloaded operator for addition with assignment
Vector3& operator+=(const Vector3& vector);
// Overloaded operator for substraction with assignment
/// Overloaded operator for substraction with assignment
Vector3& operator-=(const Vector3& vector);
// Overloaded operator for multiplication with a number with assignment
/// Overloaded operator for multiplication with a number with assignment
Vector3& operator*=(decimal number);
// Overloaded operator for division by a number with assignment
/// Overloaded operator for division by a number with assignment
Vector3& operator/=(decimal number);
// Overloaded operator for value access
/// Overloaded operator for value access
decimal& operator[] (int index);
// Overloaded operator for value access
/// Overloaded operator for value access
const decimal& operator[] (int index) const;
// Overloaded operator
/// Overloaded operator
Vector3& operator=(const Vector3& vector);
// -------------------- Friends -------------------- //

View File

@ -30,13 +30,13 @@
#include "../configuration.h"
#include "../decimal.h"
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
// ---------- Mathematics functions ---------- //
// function to test if two real numbers are (almost) equal
// We test if two numbers a and b are such that (a-b) are in [-EPSILON; EPSILON]
/// function to test if two real numbers are (almost) equal
/// We test if two numbers a and b are such that (a-b) are in [-EPSILON; EPSILON]
inline bool approxEqual(decimal a, decimal b, decimal epsilon = 1.0e-10) {
decimal difference = a - b;
return (difference < epsilon && difference > -epsilon);

View File

@ -37,88 +37,88 @@
// C++ cast operator like reinterpret_cast<>, ...
// ReactPhysics3D namespace
/// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class MemoryPool :
This class represents a memory pool that allows us to allocate
dynamic memory at the beginning of the application in order to
avoid memory fragmentation and also a large number of allocation
and deallocation.
-------------------------------------------------------------------
*/
// Class MemoryPool
/**
* This class represents a memory pool. This memory pool allows us to allocate
* dynamic memory at the beginning of the application in order to
* avoid memory fragmentation and also a large number of allocation
* and deallocation.
*/
template<class T>
class MemoryPool {
private:
// MemoryUnit represents a unit of memory
/// MemoryUnit represents a unit of memory
struct MemoryUnit {
struct MemoryUnit* pNext; // Pointer to the next memory unit
struct MemoryUnit* pPrevious; // Pointer to the previous memory unit
};
// Memory block (that contains several memory units)
/// Memory block (that contains several memory units)
struct MemoryBlock {
struct MemoryBlock* pNext; // Pointer to the next memory block
};
// -------------------- Constants -------------------- //
static const uint NB_OBJECTS_FIRST_BLOCK; // Number of objects allocated in the first block
// Number of objects allocated in the first block
static const uint NB_OBJECTS_FIRST_BLOCK;
// -------------------- Attributes -------------------- //
// Pointer to the first allocated memory block
/// Pointer to the first allocated memory block
void* mPBlocks;
// Pointer to the first allocated memory unit
/// Pointer to the first allocated memory unit
MemoryUnit* mPAllocatedUnits;
// Pointer to the first free memory unit
/// Pointer to the first free memory unit
MemoryUnit* mPFreeUnits;
// Current number of objects in the pool
/// Current number of objects in the pool
uint mCurrentNbObjects;
// Current maximum number of objects that can be allocated in the pool
/// Current maximum number of objects that can be allocated in the pool
uint mCapacity;
// Number of objects to allocate in the next block
/// Number of objects to allocate in the next block
uint mNbObjectsNextBlock;
// -------------------- Methods -------------------- //
// Private copy-constructor
/// Private copy-constructor
MemoryPool(const MemoryPool& body);
// Private assignment operator
/// Private assignment operator
MemoryPool& operator=(const MemoryPool& timer);
// Allocate more memory (more blocks) when needed
/// Allocate more memory (more blocks) when needed
void allocateMemory();
public:
// -------------------- Methods -------------------- //
// Constructor
/// Constructor
MemoryPool(uint capacity = 0) throw(std::bad_alloc);
// Destructor
/// Destructor
~MemoryPool();
// Return the current maximum number of objects allowed in the pool
/// Return the current maximum number of objects allowed in the pool
uint getCapacity() const;
// Return the current number of objects in the pool
/// Return the current number of objects in the pool
uint getCurrentNbObjects() const;
// Return a pointer to an memory allocated location to store a new object
/// Return a pointer to an memory allocated location to store a new object
void* allocateObject();
// Tell the pool that an object doesn't need to be store in the pool anymore
/// Tell the pool that an object doesn't need to be store in the pool anymore
void freeObject(void* pObjectToFree);
};
@ -126,8 +126,8 @@ class MemoryPool {
template<class T> const uint MemoryPool<T>::NB_OBJECTS_FIRST_BLOCK = 100;
// Constructor
// Allocate a large block of memory in order to contain
// a given number of object of the template type T
/// Allocate a large block of memory in order to contain
/// a given number of object of the template type T
template<class T>
MemoryPool<T>::MemoryPool(uint capacity) throw(std::bad_alloc)
: mCurrentNbObjects(0), mCapacity(capacity) {
@ -142,7 +142,7 @@ MemoryPool<T>::MemoryPool(uint capacity) throw(std::bad_alloc)
}
// Destructor
// Deallocate the blocks of memory that have been allocated previously
/// Deallocate the blocks of memory that have been allocated previously
template<class T>
MemoryPool<T>::~MemoryPool() {
@ -158,9 +158,9 @@ MemoryPool<T>::~MemoryPool() {
}
}
// Return a pointer to a memory allocated location to store a new object
// This method only allocates memory if needed and it returns a pointer
// to a location in an allocated block of memory where a new object can be stored
// Return a pointer to a memory allocated location to store a new object.
/// This method only allocates memory if needed and it returns a pointer
/// to a location in an allocated block of memory where a new object can be stored
template<class T>
void* MemoryPool<T>::allocateObject() {
@ -193,10 +193,10 @@ void* MemoryPool<T>::allocateObject() {
}
// Tell the pool that an object does not need to be stored in the pool anymore
// This method does not deallocate memory because it will be done only at the
// end but it notifies the memory pool that an object that was stored in the pool
// does not need to be stored anymore and therefore we can use the corresponding
// location in the pool for another object
/// This method does not deallocate memory because it will be done only at the
/// end but it notifies the memory pool that an object that was stored in the pool
/// does not need to be stored anymore and therefore we can use the corresponding
/// location in the pool for another object
template<class T>
void MemoryPool<T>::freeObject(void* pObjectToFree) {
@ -218,9 +218,10 @@ void MemoryPool<T>::freeObject(void* pObjectToFree) {
mCurrentNbObjects--;
}
// Allocate more memory. This method is called when there are no
// free memory units available anymore. Therefore, we need to allocate
// a new memory block in order to be able to store several new memory units.
// Allocate more memory (more blocks) when needed
/// This method is called when there are no
/// free memory units available anymore. Therefore, we need to allocate
/// a new memory block in order to be able to store several new memory units.
template<class T>
void MemoryPool<T>::allocateMemory() {

View File

@ -48,7 +48,7 @@
#include "collision/shapes/CylinderShape.h"
#include "collision/shapes/AABB.h"
// Alias to the ReactPhysics3D namespace
/// Alias to the ReactPhysics3D namespace
namespace rp3d = reactphysics3d;
#endif