Merge branch 'opti_solver2' into optimization

This commit is contained in:
Daniel Chappuis 2016-10-24 21:01:44 +02:00
commit 05f665040f
39 changed files with 718 additions and 1164 deletions

View File

@ -147,7 +147,6 @@ SET (REACTPHYSICS3D_SOURCES
"src/engine/DynamicsWorld.h"
"src/engine/DynamicsWorld.cpp"
"src/engine/EventListener.h"
"src/engine/Impulse.h"
"src/engine/Island.h"
"src/engine/Island.cpp"
"src/engine/Material.h"
@ -174,8 +173,10 @@ SET (REACTPHYSICS3D_SOURCES
"src/mathematics/Vector3.h"
"src/mathematics/Ray.h"
"src/mathematics/Vector3.cpp"
"src/memory/MemoryAllocator.h"
"src/memory/MemoryAllocator.cpp"
"src/memory/PoolAllocator.h"
"src/memory/PoolAllocator.cpp"
"src/memory/SingleFrameAllocator.h"
"src/memory/SingleFrameAllocator.cpp"
"src/memory/Stack.h"
)

View File

@ -70,7 +70,7 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape,
const Transform& transform) {
// Create a new proxy collision shape to attach the collision shape to the body
ProxyShape* proxyShape = new (mWorld.mMemoryAllocator.allocate(
ProxyShape* proxyShape = new (mWorld.mPoolAllocator.allocate(
sizeof(ProxyShape))) ProxyShape(this, collisionShape,
transform, decimal(1));
@ -116,7 +116,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) {
}
current->~ProxyShape();
mWorld.mMemoryAllocator.release(current, sizeof(ProxyShape));
mWorld.mPoolAllocator.release(current, sizeof(ProxyShape));
mNbCollisionShapes--;
return;
}
@ -136,7 +136,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) {
}
elementToRemove->~ProxyShape();
mWorld.mMemoryAllocator.release(elementToRemove, sizeof(ProxyShape));
mWorld.mPoolAllocator.release(elementToRemove, sizeof(ProxyShape));
mNbCollisionShapes--;
return;
}
@ -162,7 +162,7 @@ void CollisionBody::removeAllCollisionShapes() {
}
current->~ProxyShape();
mWorld.mMemoryAllocator.release(current, sizeof(ProxyShape));
mWorld.mPoolAllocator.release(current, sizeof(ProxyShape));
// Get the next element in the list
current = nextElement;
@ -181,7 +181,7 @@ void CollisionBody::resetContactManifoldsList() {
// Delete the current element
currentElement->~ContactManifoldListElement();
mWorld.mMemoryAllocator.release(currentElement, sizeof(ContactManifoldListElement));
mWorld.mPoolAllocator.release(currentElement, sizeof(ContactManifoldListElement));
currentElement = nextElement;
}

View File

@ -34,7 +34,7 @@
#include "collision/shapes/AABB.h"
#include "collision/shapes/CollisionShape.h"
#include "collision/RaycastInfo.h"
#include "memory/MemoryAllocator.h"
#include "memory/PoolAllocator.h"
#include "configuration.h"
/// Namespace reactphysics3d

View File

@ -46,6 +46,9 @@ RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyinde
// Compute the inverse mass
mMassInverse = decimal(1.0) / mInitMass;
// Update the world inverse inertia tensor
updateInertiaTensorInverseWorld();
}
// Destructor
@ -90,11 +93,15 @@ void RigidBody::setType(BodyType type) {
mMassInverse = decimal(0.0);
mInertiaTensorLocal.setToZero();
mInertiaTensorLocalInverse.setToZero();
mInertiaTensorInverseWorld.setToZero();
}
else { // If it is a dynamic body
mMassInverse = decimal(1.0) / mInitMass;
mInertiaTensorLocalInverse = mInertiaTensorLocal.getInverse();
// Update the world inverse inertia tensor
updateInertiaTensorInverseWorld();
}
// Awake the body
@ -125,6 +132,9 @@ void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) {
// Compute the inverse local inertia tensor
mInertiaTensorLocalInverse = mInertiaTensorLocal.getInverse();
// Update the world inverse inertia tensor
updateInertiaTensorInverseWorld();
}
// Set the local center of mass of the body (in local-space coordinates)
@ -166,7 +176,7 @@ void RigidBody::setMass(decimal mass) {
}
// Remove a joint from the joints list
void RigidBody::removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Joint* joint) {
void RigidBody::removeJointFromJointsList(PoolAllocator& memoryAllocator, const Joint* joint) {
assert(joint != nullptr);
assert(mJointsList != nullptr);
@ -214,7 +224,7 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape,
decimal mass) {
// Create a new proxy collision shape to attach the collision shape to the body
ProxyShape* proxyShape = new (mWorld.mMemoryAllocator.allocate(
ProxyShape* proxyShape = new (mWorld.mPoolAllocator.allocate(
sizeof(ProxyShape))) ProxyShape(this, collisionShape,
transform, mass);
@ -314,6 +324,9 @@ void RigidBody::setTransform(const Transform& transform) {
// Update the linear velocity of the center of mass
mLinearVelocity += mAngularVelocity.cross(mCenterOfMassWorld - oldCenterOfMass);
// Update the world inverse inertia tensor
updateInertiaTensorInverseWorld();
// Update the broad-phase state of the body
updateBroadPhaseState();
}
@ -326,6 +339,7 @@ void RigidBody::recomputeMassInformation() {
mMassInverse = decimal(0.0);
mInertiaTensorLocal.setToZero();
mInertiaTensorLocalInverse.setToZero();
mInertiaTensorInverseWorld.setToZero();
mCenterOfMassLocal.setToZero();
// If it is STATIC or KINEMATIC body
@ -386,6 +400,9 @@ void RigidBody::recomputeMassInformation() {
// Compute the local inverse inertia tensor
mInertiaTensorLocalInverse = mInertiaTensorLocal.getInverse();
// Update the world inverse inertia tensor
updateInertiaTensorInverseWorld();
// Update the linear velocity of the center of mass
mLinearVelocity += mAngularVelocity.cross(mCenterOfMassWorld - oldCenterOfMass);
}

View File

@ -31,7 +31,7 @@
#include "CollisionBody.h"
#include "engine/Material.h"
#include "mathematics/mathematics.h"
#include "memory/MemoryAllocator.h"
#include "memory/PoolAllocator.h"
/// Namespace reactphysics3d
namespace reactphysics3d {
@ -83,6 +83,9 @@ class RigidBody : public CollisionBody {
/// Inverse of the inertia tensor of the body
Matrix3x3 mInertiaTensorLocalInverse;
/// Inverse of the world inertia tensor of the body
Matrix3x3 mInertiaTensorInverseWorld;
/// Inverse of the mass of the body
decimal mMassInverse;
@ -104,7 +107,7 @@ class RigidBody : public CollisionBody {
// -------------------- Methods -------------------- //
/// Remove a joint from the joints list
void removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Joint* joint);
void removeJointFromJointsList(PoolAllocator& memoryAllocator, const Joint* joint);
/// Update the transform of the body after a change of the center of mass
void updateTransformWithCenterOfMass();
@ -112,6 +115,9 @@ class RigidBody : public CollisionBody {
/// Update the broad-phase state for this body (because it has moved for instance)
virtual void updateBroadPhaseState() const override;
/// Update the world inverse inertia tensor of the body
void updateInertiaTensorInverseWorld();
public :
// -------------------- Methods -------------------- //
@ -291,12 +297,19 @@ inline Matrix3x3 RigidBody::getInertiaTensorWorld() const {
*/
inline Matrix3x3 RigidBody::getInertiaTensorInverseWorld() const {
// TODO : DO NOT RECOMPUTE THE MATRIX MULTIPLICATION EVERY TIME. WE NEED TO STORE THE
// INVERSE WORLD TENSOR IN THE CLASS AND UPLDATE IT WHEN THE ORIENTATION OF THE BODY CHANGES
// Compute and return the inertia tensor in world coordinates
return mTransform.getOrientation().getMatrix() * mInertiaTensorLocalInverse *
mTransform.getOrientation().getMatrix().getTranspose();
return mInertiaTensorInverseWorld;
}
// Update the world inverse inertia tensor of the body
/// 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 void RigidBody::updateInertiaTensorInverseWorld() {
Matrix3x3 orientation = mTransform.getOrientation().getMatrix();
mInertiaTensorInverseWorld = orientation * mInertiaTensorLocalInverse * orientation.getTranspose();
}
// Return true if the gravity needs to be applied to this rigid body

View File

@ -41,7 +41,7 @@ using namespace reactphysics3d;
using namespace std;
// Constructor
CollisionDetection::CollisionDetection(CollisionWorld* world, MemoryAllocator& memoryAllocator)
CollisionDetection::CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator)
: mMemoryAllocator(memoryAllocator),
mWorld(world), mBroadPhaseAlgorithm(*this),
mIsCollisionShapesAdded(false) {
@ -189,7 +189,7 @@ void CollisionDetection::computeNarrowPhase() {
// Destroy the overlapping pair
itToRemove->second->~OverlappingPair();
mWorld->mMemoryAllocator.release(itToRemove->second, sizeof(OverlappingPair));
mWorld->mPoolAllocator.release(itToRemove->second, sizeof(OverlappingPair));
mOverlappingPairs.erase(itToRemove);
continue;
}
@ -294,7 +294,7 @@ void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* call
// Destroy the overlapping pair
itToRemove->second->~OverlappingPair();
mWorld->mMemoryAllocator.release(itToRemove->second, sizeof(OverlappingPair));
mWorld->mPoolAllocator.release(itToRemove->second, sizeof(OverlappingPair));
mOverlappingPairs.erase(itToRemove);
continue;
}
@ -370,8 +370,8 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro
shape2->getCollisionShape()->getType());
// Create the overlapping pair and add it into the set of overlapping pairs
OverlappingPair* newPair = new (mWorld->mMemoryAllocator.allocate(sizeof(OverlappingPair)))
OverlappingPair(shape1, shape2, nbMaxManifolds, mWorld->mMemoryAllocator);
OverlappingPair* newPair = new (mWorld->mPoolAllocator.allocate(sizeof(OverlappingPair)))
OverlappingPair(shape1, shape2, nbMaxManifolds, mWorld->mPoolAllocator);
assert(newPair != nullptr);
#ifndef NDEBUG
@ -400,7 +400,7 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) {
// Destroy the overlapping pair
itToRemove->second->~OverlappingPair();
mWorld->mMemoryAllocator.release(itToRemove->second, sizeof(OverlappingPair));
mWorld->mPoolAllocator.release(itToRemove->second, sizeof(OverlappingPair));
mOverlappingPairs.erase(itToRemove);
}
else {
@ -434,7 +434,7 @@ void CollisionDetection::createContact(OverlappingPair* overlappingPair,
const ContactPointInfo& contactInfo) {
// Create a new contact
ContactPoint* contact = new (mWorld->mMemoryAllocator.allocate(sizeof(ContactPoint)))
ContactPoint* contact = new (mWorld->mPoolAllocator.allocate(sizeof(ContactPoint)))
ContactPoint(contactInfo);
// Add the contact to the contact manifold set of the corresponding overlapping pair
@ -477,7 +477,7 @@ void CollisionDetection::addContactManifoldToBody(OverlappingPair* pair) {
// Add the contact manifold at the beginning of the linked
// list of contact manifolds of the first body
void* allocatedMemory1 = mWorld->mMemoryAllocator.allocate(sizeof(ContactManifoldListElement));
void* allocatedMemory1 = mWorld->mPoolAllocator.allocate(sizeof(ContactManifoldListElement));
ContactManifoldListElement* listElement1 = new (allocatedMemory1)
ContactManifoldListElement(contactManifold,
body1->mContactManifoldsList);
@ -485,7 +485,7 @@ void CollisionDetection::addContactManifoldToBody(OverlappingPair* pair) {
// Add the contact manifold at the beginning of the linked
// list of the contact manifolds of the second body
void* allocatedMemory2 = mWorld->mMemoryAllocator.allocate(sizeof(ContactManifoldListElement));
void* allocatedMemory2 = mWorld->mPoolAllocator.allocate(sizeof(ContactManifoldListElement));
ContactManifoldListElement* listElement2 = new (allocatedMemory2)
ContactManifoldListElement(contactManifold,
body2->mContactManifoldsList);
@ -520,8 +520,8 @@ EventListener* CollisionDetection::getWorldEventListener() {
}
/// Return a reference to the world memory allocator
MemoryAllocator& CollisionDetection::getWorldMemoryAllocator() {
return mWorld->mMemoryAllocator;
PoolAllocator& CollisionDetection::getWorldMemoryAllocator() {
return mWorld->mPoolAllocator;
}
// Called by a narrow-phase collision algorithm when a new contact has been found

View File

@ -32,7 +32,7 @@
#include "engine/OverlappingPair.h"
#include "engine/EventListener.h"
#include "narrowphase/DefaultCollisionDispatch.h"
#include "memory/MemoryAllocator.h"
#include "memory/PoolAllocator.h"
#include "constraint/ContactPoint.h"
#include <vector>
#include <set>
@ -93,7 +93,7 @@ class CollisionDetection : public NarrowPhaseCallback {
NarrowPhaseAlgorithm* mCollisionMatrix[NB_COLLISION_SHAPE_TYPES][NB_COLLISION_SHAPE_TYPES];
/// Reference to the memory allocator
MemoryAllocator& mMemoryAllocator;
PoolAllocator& mMemoryAllocator;
/// Pointer to the physics world
CollisionWorld* mWorld;
@ -143,7 +143,7 @@ class CollisionDetection : public NarrowPhaseCallback {
// -------------------- Methods -------------------- //
/// Constructor
CollisionDetection(CollisionWorld* world, MemoryAllocator& memoryAllocator);
CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator);
/// Destructor
~CollisionDetection() = default;
@ -220,7 +220,7 @@ class CollisionDetection : public NarrowPhaseCallback {
EventListener* getWorldEventListener();
/// Return a reference to the world memory allocator
MemoryAllocator& getWorldMemoryAllocator();
PoolAllocator& getWorldMemoryAllocator();
/// Called by a narrow-phase collision algorithm when a new contact has been found
virtual void notifyContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo) override;

View File

@ -31,7 +31,7 @@ using namespace reactphysics3d;
// Constructor
ContactManifold::ContactManifold(ProxyShape* shape1, ProxyShape* shape2,
MemoryAllocator& memoryAllocator, short normalDirectionId)
PoolAllocator& memoryAllocator, short normalDirectionId)
: mShape1(shape1), mShape2(shape2), mNormalDirectionId(normalDirectionId),
mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0),
mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false),

View File

@ -31,7 +31,7 @@
#include "body/CollisionBody.h"
#include "collision/ProxyShape.h"
#include "constraint/ContactPoint.h"
#include "memory/MemoryAllocator.h"
#include "memory/PoolAllocator.h"
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -102,7 +102,7 @@ class ContactManifold {
short int mNormalDirectionId;
/// Number of contacts in the cache
uint mNbContactPoints;
int8 mNbContactPoints;
/// First friction vector of the contact manifold
Vector3 mFrictionVector1;
@ -126,7 +126,7 @@ class ContactManifold {
bool mIsAlreadyInIsland;
/// Reference to the memory allocator
MemoryAllocator& mMemoryAllocator;
PoolAllocator& mMemoryAllocator;
// -------------------- Methods -------------------- //
@ -151,7 +151,7 @@ class ContactManifold {
/// Constructor
ContactManifold(ProxyShape* shape1, ProxyShape* shape2,
MemoryAllocator& memoryAllocator, short int normalDirectionId);
PoolAllocator& memoryAllocator, short int normalDirectionId);
/// Destructor
~ContactManifold();
@ -187,7 +187,7 @@ class ContactManifold {
void clear();
/// Return the number of contact points in the manifold
uint getNbContactPoints() const;
int8 getNbContactPoints() const;
/// Return the first friction vector at the center of the contact manifold
const Vector3& getFrictionVector1() const;
@ -264,7 +264,7 @@ inline short int ContactManifold::getNormalDirectionId() const {
}
// Return the number of contact points in the manifold
inline uint ContactManifold::getNbContactPoints() const {
inline int8 ContactManifold::getNbContactPoints() const {
return mNbContactPoints;
}

View File

@ -30,7 +30,7 @@ using namespace reactphysics3d;
// Constructor
ContactManifoldSet::ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2,
MemoryAllocator& memoryAllocator, int nbMaxManifolds)
PoolAllocator& memoryAllocator, int nbMaxManifolds)
: mNbMaxManifolds(nbMaxManifolds), mNbManifolds(0), mShape1(shape1),
mShape2(shape2), mMemoryAllocator(memoryAllocator) {
assert(nbMaxManifolds >= 1);

View File

@ -61,7 +61,7 @@ class ContactManifoldSet {
ProxyShape* mShape2;
/// Reference to the memory allocator
MemoryAllocator& mMemoryAllocator;
PoolAllocator& mMemoryAllocator;
/// Contact manifolds of the set
ContactManifold* mManifolds[MAX_MANIFOLDS_IN_CONTACT_MANIFOLD_SET];
@ -88,7 +88,7 @@ class ContactManifoldSet {
/// Constructor
ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2,
MemoryAllocator& memoryAllocator, int nbMaxManifolds);
PoolAllocator& memoryAllocator, int nbMaxManifolds);
/// Destructor
~ContactManifoldSet();

View File

@ -51,7 +51,7 @@ class CollisionDispatch {
/// Initialize the collision dispatch configuration
virtual void init(CollisionDetection* collisionDetection,
MemoryAllocator* memoryAllocator) {
PoolAllocator* memoryAllocator) {
}

View File

@ -31,7 +31,7 @@ using namespace reactphysics3d;
/// Initialize the collision dispatch configuration
void DefaultCollisionDispatch::init(CollisionDetection* collisionDetection,
MemoryAllocator* memoryAllocator) {
PoolAllocator* memoryAllocator) {
// Initialize the collision algorithms
mSphereVsSphereAlgorithm.init(collisionDetection, memoryAllocator);

View File

@ -63,7 +63,7 @@ class DefaultCollisionDispatch : public CollisionDispatch {
/// Initialize the collision dispatch configuration
virtual void init(CollisionDetection* collisionDetection,
MemoryAllocator* memoryAllocator) override;
PoolAllocator* memoryAllocator) override;
/// Select and return the narrow-phase collision detection algorithm to
/// use between two types of collision shapes.

View File

@ -34,7 +34,7 @@
#include "collision/narrowphase/NarrowPhaseAlgorithm.h"
#include "mathematics/mathematics.h"
#include "TriangleEPA.h"
#include "memory/MemoryAllocator.h"
#include "memory/PoolAllocator.h"
#include <algorithm>
/// ReactPhysics3D namespace
@ -88,7 +88,7 @@ class EPAAlgorithm {
// -------------------- Attributes -------------------- //
/// Reference to the memory allocator
MemoryAllocator* mMemoryAllocator;
PoolAllocator* mMemoryAllocator;
/// Triangle comparison operator
TriangleComparison mTriangleComparison;
@ -120,7 +120,7 @@ class EPAAlgorithm {
EPAAlgorithm& operator=(const EPAAlgorithm& algorithm) = delete;
/// Initalize the algorithm
void init(MemoryAllocator* memoryAllocator);
void init(PoolAllocator* memoryAllocator);
/// Compute the penetration depth with EPA algorithm.
bool computePenetrationDepthAndContactPoints(const VoronoiSimplex& simplex,
@ -151,7 +151,7 @@ inline void EPAAlgorithm::addFaceCandidate(TriangleEPA* triangle, TriangleEPA**
}
// Initalize the algorithm
inline void EPAAlgorithm::init(MemoryAllocator* memoryAllocator) {
inline void EPAAlgorithm::init(PoolAllocator* memoryAllocator) {
mMemoryAllocator = memoryAllocator;
}

View File

@ -94,7 +94,7 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm {
/// Initalize the algorithm
virtual void init(CollisionDetection* collisionDetection,
MemoryAllocator* memoryAllocator) override;
PoolAllocator* memoryAllocator) override;
/// Compute a contact info if the two bounding volumes collide.
virtual void testCollision(const CollisionShapeInfo& shape1Info,
@ -110,7 +110,7 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm {
// Initalize the algorithm
inline void GJKAlgorithm::init(CollisionDetection* collisionDetection,
MemoryAllocator* memoryAllocator) {
PoolAllocator* memoryAllocator) {
NarrowPhaseAlgorithm::init(collisionDetection, memoryAllocator);
mAlgoEPA.init(memoryAllocator);
}

View File

@ -563,7 +563,6 @@ bool VoronoiSimplex::computeClosestPointOnTetrahedron(const Vector3& a, const Ve
if (squareDist < closestSquareDistance) {
// Use it as the current closest point
closestSquareDistance = squareDist;
baryCoordsAB.setAllValues(0.0, triangleBaryCoords[0]);
baryCoordsCD.setAllValues(triangleBaryCoords[2], triangleBaryCoords[1]);
bitsUsedPoints = mapTriangleUsedVerticesToTetrahedron(tempUsedVertices, 1, 3, 2);

View File

@ -36,7 +36,7 @@ NarrowPhaseAlgorithm::NarrowPhaseAlgorithm()
}
// Initalize the algorithm
void NarrowPhaseAlgorithm::init(CollisionDetection* collisionDetection, MemoryAllocator* memoryAllocator) {
void NarrowPhaseAlgorithm::init(CollisionDetection* collisionDetection, PoolAllocator* memoryAllocator) {
mCollisionDetection = collisionDetection;
mMemoryAllocator = memoryAllocator;
}

View File

@ -29,7 +29,7 @@
// Libraries
#include "body/Body.h"
#include "constraint/ContactPoint.h"
#include "memory/MemoryAllocator.h"
#include "memory/PoolAllocator.h"
#include "engine/OverlappingPair.h"
#include "collision/CollisionShapeInfo.h"
@ -71,7 +71,7 @@ class NarrowPhaseAlgorithm {
CollisionDetection* mCollisionDetection;
/// Pointer to the memory allocator
MemoryAllocator* mMemoryAllocator;
PoolAllocator* mMemoryAllocator;
/// Overlapping pair of the bodies currently tested for collision
OverlappingPair* mCurrentOverlappingPair;
@ -93,7 +93,7 @@ class NarrowPhaseAlgorithm {
NarrowPhaseAlgorithm& operator=(const NarrowPhaseAlgorithm& algorithm) = delete;
/// Initalize the algorithm
virtual void init(CollisionDetection* collisionDetection, MemoryAllocator* memoryAllocator);
virtual void init(CollisionDetection* collisionDetection, PoolAllocator* memoryAllocator);
/// Set the current overlapping pair of bodies
void setCurrentOverlappingPair(OverlappingPair* overlappingPair);

View File

@ -34,7 +34,7 @@
#include "mathematics/Ray.h"
#include "AABB.h"
#include "collision/RaycastInfo.h"
#include "memory/MemoryAllocator.h"
#include "memory/PoolAllocator.h"
/// ReactPhysics3D namespace
namespace reactphysics3d {

View File

@ -30,6 +30,7 @@
#include <limits>
#include <cfloat>
#include <utility>
#include <cstdint>
#include "decimal.h"
// Windows platform
@ -51,10 +52,9 @@ using luint = long unsigned int;
using bodyindex = luint;
using bodyindexpair = std::pair<bodyindex, bodyindex>;
using int16 = signed short;
using int32 = signed int;
using uint16 = unsigned short;
using uint32 = unsigned int;
using int8 = int8_t;
using int16 = int16_t;
using int32 = int32_t;
// ------------------- Enumerations ------------------- //
@ -144,6 +144,9 @@ constexpr int NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE = 1;
/// least one concave collision shape.
constexpr int NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE = 3;
/// Size (in bytes) of the single frame allocator
constexpr size_t SIZE_SINGLE_FRAME_ALLOCATOR_BYTES = 15728640; // 15 Mb
}
#endif

View File

@ -45,9 +45,6 @@ ContactPoint::ContactPoint(const ContactPointInfo& contactInfo)
contactInfo.localPoint2),
mIsRestingContact(false) {
mFrictionVectors[0] = Vector3(0, 0, 0);
mFrictionVectors[1] = Vector3(0, 0, 0);
assert(mPenetrationDepth > 0.0);
assert(mPenetrationDepth > decimal(0.0));
}

View File

@ -128,21 +128,9 @@ class ContactPoint {
/// 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
Vector3 mFrictionVectors[2];
/// Cached penetration impulse
decimal mPenetrationImpulse;
/// Cached first friction impulse
decimal mFrictionImpulse1;
/// Cached second friction impulse
decimal mFrictionImpulse2;
/// Cached rolling resistance impulse
Vector3 mRollingResistanceImpulse;
public :
// -------------------- Methods -------------------- //
@ -186,27 +174,9 @@ class ContactPoint {
/// Return the cached penetration impulse
decimal getPenetrationImpulse() const;
/// Return the cached first friction impulse
decimal getFrictionImpulse1() const;
/// Return the cached second friction impulse
decimal getFrictionImpulse2() const;
/// Return the cached rolling resistance impulse
Vector3 getRollingResistanceImpulse() const;
/// Set the cached penetration impulse
void setPenetrationImpulse(decimal impulse);
/// Set the first cached friction impulse
void setFrictionImpulse1(decimal impulse);
/// Set the second cached friction impulse
void setFrictionImpulse2(decimal impulse);
/// Set the cached rolling resistance impulse
void setRollingResistanceImpulse(const Vector3& impulse);
/// Set the contact world point on body 1
void setWorldPointOnBody1(const Vector3& worldPoint);
@ -219,18 +189,6 @@ class ContactPoint {
/// Set the mIsRestingContact variable
void setIsRestingContact(bool isRestingContact);
/// Get the first friction vector
Vector3 getFrictionVector1() const;
/// Set the first friction vector
void setFrictionVector1(const Vector3& frictionVector1);
/// Get the second friction vector
Vector3 getFrictionVector2() const;
/// Set the second friction vector
void setFrictionVector2(const Vector3& frictionVector2);
/// Return the penetration depth
decimal getPenetrationDepth() const;
@ -283,41 +241,11 @@ inline decimal ContactPoint::getPenetrationImpulse() const {
return mPenetrationImpulse;
}
// Return the cached first friction impulse
inline decimal ContactPoint::getFrictionImpulse1() const {
return mFrictionImpulse1;
}
// Return the cached second friction impulse
inline decimal ContactPoint::getFrictionImpulse2() const {
return mFrictionImpulse2;
}
// Return the cached rolling resistance impulse
inline Vector3 ContactPoint::getRollingResistanceImpulse() const {
return mRollingResistanceImpulse;
}
// Set the cached penetration impulse
inline void ContactPoint::setPenetrationImpulse(decimal impulse) {
mPenetrationImpulse = impulse;
}
// Set the first cached friction impulse
inline void ContactPoint::setFrictionImpulse1(decimal impulse) {
mFrictionImpulse1 = impulse;
}
// Set the second cached friction impulse
inline void ContactPoint::setFrictionImpulse2(decimal impulse) {
mFrictionImpulse2 = impulse;
}
// Set the cached rolling resistance impulse
inline void ContactPoint::setRollingResistanceImpulse(const Vector3& impulse) {
mRollingResistanceImpulse = impulse;
}
// Set the contact world point on body 1
inline void ContactPoint::setWorldPointOnBody1(const Vector3& worldPoint) {
mWorldPointOnBody1 = worldPoint;
@ -338,26 +266,6 @@ inline void ContactPoint::setIsRestingContact(bool isRestingContact) {
mIsRestingContact = isRestingContact;
}
// Get the first friction vector
inline Vector3 ContactPoint::getFrictionVector1() const {
return mFrictionVectors[0];
}
// Set the first friction vector
inline void ContactPoint::setFrictionVector1(const Vector3& frictionVector1) {
mFrictionVectors[0] = frictionVector1;
}
// Get the second friction vector
inline Vector3 ContactPoint::getFrictionVector2() const {
return mFrictionVectors[1];
}
// Set the second friction vector
inline void ContactPoint::setFrictionVector2(const Vector3& frictionVector2) {
mFrictionVectors[1] = frictionVector2;
}
// Return the penetration depth of the contact
inline decimal ContactPoint::getPenetrationDepth() const {
return mPenetrationDepth;

View File

@ -33,7 +33,7 @@ using namespace std;
// Constructor
CollisionWorld::CollisionWorld()
: mCollisionDetection(this, mMemoryAllocator), mCurrentBodyID(0),
: mCollisionDetection(this, mPoolAllocator), mCurrentBodyID(0),
mEventListener(nullptr) {
}
@ -66,7 +66,7 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) {
assert(bodyID < std::numeric_limits<reactphysics3d::bodyindex>::max());
// Create the collision body
CollisionBody* collisionBody = new (mMemoryAllocator.allocate(sizeof(CollisionBody)))
CollisionBody* collisionBody = new (mPoolAllocator.allocate(sizeof(CollisionBody)))
CollisionBody(transform, *this, bodyID);
assert(collisionBody != nullptr);
@ -97,7 +97,7 @@ void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) {
mBodies.erase(collisionBody);
// Free the object from the memory allocator
mMemoryAllocator.release(collisionBody, sizeof(CollisionBody));
mPoolAllocator.release(collisionBody, sizeof(CollisionBody));
}
// Return the next available body ID

View File

@ -39,7 +39,7 @@
#include "collision/CollisionDetection.h"
#include "constraint/Joint.h"
#include "constraint/ContactPoint.h"
#include "memory/MemoryAllocator.h"
#include "memory/PoolAllocator.h"
#include "EventListener.h"
/// Namespace reactphysics3d
@ -72,8 +72,8 @@ class CollisionWorld {
/// List of free ID for rigid bodies
std::vector<luint> mFreeBodiesIDs;
/// Memory allocator
MemoryAllocator mMemoryAllocator;
/// Pool Memory allocator
PoolAllocator mPoolAllocator;
/// Pointer to an event listener object
EventListener* mEventListener;

File diff suppressed because it is too large Load Diff

View File

@ -32,7 +32,6 @@
#include "constraint/Joint.h"
#include "collision/ContactManifold.h"
#include "Island.h"
#include "Impulse.h"
#include <map>
#include <set>
@ -120,80 +119,41 @@ class ContactSolver {
*/
struct ContactPointSolver {
/// 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;
/// Accumulated rolling resistance impulse
Vector3 rollingResistanceImpulse;
/// Pointer to the external contact
ContactPoint* externalContact;
/// 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;
/// Accumulated normal impulse
decimal penetrationImpulse;
/// Accumulated split impulse for penetration correction
decimal penetrationSplitImpulse;
/// Inverse of the matrix K for the penenetration
decimal inversePenetrationMass;
/// Inverse of the matrix K for the 1st friction
decimal inverseFriction1Mass;
/// Cross product of r1 with the contact normal
Vector3 i1TimesR1CrossN;
/// Inverse of the matrix K for the 2nd friction
decimal inverseFriction2Mass;
/// Cross product of r2 with the contact normal
Vector3 i2TimesR2CrossN;
/// True if the contact was existing last time step
bool isRestingContact;
/// Pointer to the external contact
ContactPoint* externalContact;
};
// Structure ContactManifoldSolver
@ -203,11 +163,14 @@ class ContactSolver {
*/
struct ContactManifoldSolver {
/// Pointer to the external contact manifold
ContactManifold* externalContactManifold;
/// Index of body 1 in the constraint solver
uint indexBody1;
int32 indexBody1;
/// Index of body 2 in the constraint solver
uint indexBody2;
int32 indexBody2;
/// Inverse of the mass of body 1
decimal massInverseBody1;
@ -221,30 +184,12 @@ class ContactSolver {
/// Inverse inertia tensor of body 2
Matrix3x3 inverseInertiaTensorBody2;
/// Contact point constraints
ContactPointSolver contacts[MAX_CONTACT_POINTS_IN_MANIFOLD];
/// Number of contact points
uint nbContacts;
/// True if the body 1 is of type dynamic
bool isBody1DynamicType;
/// True if the body 2 is of type dynamic
bool isBody2DynamicType;
/// Mix of the restitution factor for two bodies
decimal restitutionFactor;
/// Mix friction coefficient for the two bodies
decimal frictionCoefficient;
/// Rolling resistance factor between the two bodies
decimal rollingResistanceFactor;
/// 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
@ -309,6 +254,9 @@ class ContactSolver {
/// Rolling resistance impulse
Vector3 rollingResistanceImpulse;
/// Number of contact points
int8 nbContacts;
};
// -------------------- Constants --------------------- //
@ -336,9 +284,18 @@ class ContactSolver {
/// Contact constraints
ContactManifoldSolver* mContactConstraints;
/// Contact points
ContactPointSolver* mContactPoints;
/// Number of contact point constraints
uint mNbContactPoints;
/// Number of contact constraints
uint mNbContactManifolds;
/// Single frame memory allocator
SingleFrameAllocator& mSingleFrameAllocator;
/// Array of linear velocities
Vector3* mLinearVelocities;
@ -348,28 +305,11 @@ class ContactSolver {
/// 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
bool mIsWarmStartingActive;
/// 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
bool mIsSolveFrictionAtContactManifoldCenterActive;
// -------------------- Methods -------------------- //
/// Initialize the contact constraints before solving the system
void initializeContactConstraints();
/// 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
void applySplitImpulse(const Impulse& impulse,
const ContactManifoldSolver& manifold);
/// Compute the collision restitution factor from the restitution factor of each body
decimal computeMixedRestitutionFactor(RigidBody *body1,
RigidBody *body2) const;
@ -381,42 +321,31 @@ class ContactSolver {
/// Compute th mixed rolling resistance factor between two bodies
decimal computeMixedRollingResistance(RigidBody* body1, RigidBody* body2) const;
/// 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 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
const Impulse computePenetrationImpulse(decimal deltaLambda,
const ContactPointSolver& contactPoint) const;
/// Compute the first friction constraint impulse
const Impulse computeFriction1Impulse(decimal deltaLambda,
const ContactPointSolver& contactPoint) const;
/// Compute the second friction constraint impulse
const Impulse computeFriction2Impulse(decimal deltaLambda,
const ContactPointSolver& contactPoint) const;
/// Warm start the solver.
void warmStart();
public:
// -------------------- Methods -------------------- //
/// Constructor
ContactSolver(const std::map<RigidBody*, uint>& mapBodyToVelocityIndex);
ContactSolver(const std::map<RigidBody*, uint>& mapBodyToVelocityIndex,
SingleFrameAllocator& allocator);
/// Destructor
~ContactSolver() = default;
/// Initialize the contact constraints
void init(Island** islands, uint nbIslands, decimal timeStep);
/// Initialize the constraint solver for a given island
void initializeForIsland(decimal dt, Island* island);
void initializeForIsland(Island* island);
/// Set the split velocities arrays
void setSplitVelocitiesArrays(Vector3* splitLinearVelocities,
@ -426,9 +355,6 @@ class ContactSolver {
void setConstrainedVelocitiesArrays(Vector3* constrainedLinearVelocities,
Vector3* constrainedAngularVelocities);
/// Warm start the solver.
void warmStart();
/// Store the computed impulses to use them to
/// warm start the solver at the next iteration
void storeImpulses();
@ -441,13 +367,6 @@ class ContactSolver {
/// 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
void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive);
/// Clean up the constraint solver
void cleanup();
};
// Set the split velocities arrays
@ -482,12 +401,6 @@ inline void ContactSolver::setIsSplitImpulseActive(bool isActive) {
mIsSplitImpulseActive = isActive;
}
// Activate or deactivate the solving of friction constraints at the center of
// the contact manifold instead of solving them at each contact point
inline void ContactSolver::setIsSolveFrictionAtContactManifoldCenterActive(bool isActive) {
mIsSolveFrictionAtContactManifoldCenterActive = isActive;
}
// Compute the collision restitution factor from the restitution factor of each body
inline decimal ContactSolver::computeMixedRestitutionFactor(RigidBody* body1,
RigidBody* body2) const {
@ -502,7 +415,7 @@ inline decimal ContactSolver::computeMixedRestitutionFactor(RigidBody* body1,
inline decimal ContactSolver::computeMixedFrictionCoefficient(RigidBody *body1,
RigidBody *body2) const {
// Use the geometric mean to compute the mixed friction coefficient
return sqrt(body1->getMaterial().getFrictionCoefficient() *
return std::sqrt(body1->getMaterial().getFrictionCoefficient() *
body2->getMaterial().getFrictionCoefficient());
}
@ -512,34 +425,6 @@ inline decimal ContactSolver::computeMixedRollingResistance(RigidBody* body1,
return decimal(0.5f) * (body1->getMaterial().getRollingResistance() + body2->getMaterial().getRollingResistance());
}
// Compute a penetration constraint impulse
inline const Impulse ContactSolver::computePenetrationImpulse(decimal deltaLambda,
const ContactPointSolver& contactPoint)
const {
return Impulse(-contactPoint.normal * deltaLambda, -contactPoint.r1CrossN * deltaLambda,
contactPoint.normal * deltaLambda, contactPoint.r2CrossN * deltaLambda);
}
// Compute the first friction constraint impulse
inline const Impulse ContactSolver::computeFriction1Impulse(decimal deltaLambda,
const ContactPointSolver& contactPoint)
const {
return Impulse(-contactPoint.frictionVector1 * deltaLambda,
-contactPoint.r1CrossT1 * deltaLambda,
contactPoint.frictionVector1 * deltaLambda,
contactPoint.r2CrossT1 * deltaLambda);
}
// Compute the second friction constraint impulse
inline const Impulse ContactSolver::computeFriction2Impulse(decimal deltaLambda,
const ContactPointSolver& contactPoint)
const {
return Impulse(-contactPoint.frictionVector2 * deltaLambda,
-contactPoint.r1CrossT2 * deltaLambda,
contactPoint.frictionVector2 * deltaLambda,
contactPoint.r2CrossT2 * deltaLambda);
}
}
#endif

View File

@ -40,7 +40,8 @@ using namespace std;
*/
DynamicsWorld::DynamicsWorld(const Vector3 &gravity)
: CollisionWorld(),
mContactSolver(mMapBodyToConstrainedVelocityIndex),
mSingleFrameAllocator(SIZE_SINGLE_FRAME_ALLOCATOR_BYTES),
mContactSolver(mMapBodyToConstrainedVelocityIndex, mSingleFrameAllocator),
mConstraintSolver(mMapBodyToConstrainedVelocityIndex),
mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS),
mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS),
@ -48,8 +49,7 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity)
mIsGravityEnabled(true), mConstrainedLinearVelocities(nullptr),
mConstrainedAngularVelocities(nullptr), mSplitLinearVelocities(nullptr),
mSplitAngularVelocities(nullptr), mConstrainedPositions(nullptr),
mConstrainedOrientations(nullptr), mNbIslands(0),
mNbIslandsCapacity(0), mIslands(nullptr), mNbBodiesCapacity(0),
mConstrainedOrientations(nullptr), mNbIslands(0), mIslands(nullptr),
mSleepLinearVelocity(DEFAULT_SLEEP_LINEAR_VELOCITY),
mSleepAngularVelocity(DEFAULT_SLEEP_ANGULAR_VELOCITY),
mTimeBeforeSleep(DEFAULT_TIME_BEFORE_SLEEP) {
@ -75,29 +75,6 @@ DynamicsWorld::~DynamicsWorld() {
destroyRigidBody(*itToRemove);
}
// Release the memory allocated for the islands
for (uint i=0; i<mNbIslands; i++) {
// Call the island destructor
mIslands[i]->~Island();
// Release the allocated memory for the island
mMemoryAllocator.release(mIslands[i], sizeof(Island));
}
if (mNbIslandsCapacity > 0) {
mMemoryAllocator.release(mIslands, sizeof(Island*) * mNbIslandsCapacity);
}
// Release the memory allocated for the bodies velocity arrays
if (mNbBodiesCapacity > 0) {
delete[] mSplitLinearVelocities;
delete[] mSplitAngularVelocities;
delete[] mConstrainedLinearVelocities;
delete[] mConstrainedAngularVelocities;
delete[] mConstrainedPositions;
delete[] mConstrainedOrientations;
}
assert(mJoints.size() == 0);
assert(mRigidBodies.size() == 0);
@ -161,6 +138,9 @@ void DynamicsWorld::update(decimal timeStep) {
// Reset the external force and torque applied to the bodies
resetBodiesForceAndTorque();
// Reset the single frame memory allocator
mSingleFrameAllocator.reset();
}
// Integrate position and orientation of the rigid bodies.
@ -232,6 +212,9 @@ void DynamicsWorld::updateBodiesState() {
// Update the transform of the body (using the new center of mass and new orientation)
bodies[b]->updateTransformWithCenterOfMass();
// Update the world inverse inertia tensor of the body
bodies[b]->updateInertiaTensorInverseWorld();
// Update the broad-phase state of the body
bodies[b]->updateBroadPhaseState();
}
@ -241,31 +224,26 @@ void DynamicsWorld::updateBodiesState() {
// Initialize the bodies velocities arrays for the next simulation step.
void DynamicsWorld::initVelocityArrays() {
PROFILE("DynamicsWorld::initVelocityArrays()");
// Allocate memory for the bodies velocity arrays
uint nbBodies = mRigidBodies.size();
if (mNbBodiesCapacity != nbBodies && nbBodies > 0) {
if (mNbBodiesCapacity > 0) {
delete[] mSplitLinearVelocities;
delete[] mSplitAngularVelocities;
}
mNbBodiesCapacity = nbBodies;
// TODO : Use better memory allocation here
mSplitLinearVelocities = new Vector3[mNbBodiesCapacity];
mSplitAngularVelocities = new Vector3[mNbBodiesCapacity];
mConstrainedLinearVelocities = new Vector3[mNbBodiesCapacity];
mConstrainedAngularVelocities = new Vector3[mNbBodiesCapacity];
mConstrainedPositions = new Vector3[mNbBodiesCapacity];
mConstrainedOrientations = new Quaternion[mNbBodiesCapacity];
assert(mSplitLinearVelocities != nullptr);
assert(mSplitAngularVelocities != nullptr);
assert(mConstrainedLinearVelocities != nullptr);
assert(mConstrainedAngularVelocities != nullptr);
assert(mConstrainedPositions != nullptr);
assert(mConstrainedOrientations != nullptr);
}
mSplitLinearVelocities = static_cast<Vector3*>(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3)));
mSplitAngularVelocities = static_cast<Vector3*>(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3)));
mConstrainedLinearVelocities = static_cast<Vector3*>(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3)));
mConstrainedAngularVelocities = static_cast<Vector3*>(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3)));
mConstrainedPositions = static_cast<Vector3*>(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3)));
mConstrainedOrientations = static_cast<Quaternion*>(mSingleFrameAllocator.allocate(nbBodies * sizeof(Quaternion)));
assert(mSplitLinearVelocities != nullptr);
assert(mSplitAngularVelocities != nullptr);
assert(mConstrainedLinearVelocities != nullptr);
assert(mConstrainedAngularVelocities != nullptr);
assert(mConstrainedPositions != nullptr);
assert(mConstrainedOrientations != nullptr);
// Reset the velocities arrays
for (uint i=0; i<mNbBodiesCapacity; i++) {
for (uint i=0; i<nbBodies; i++) {
mSplitLinearVelocities[i].setToZero();
mSplitAngularVelocities[i].setToZero();
}
@ -364,23 +342,28 @@ void DynamicsWorld::solveContactsAndConstraints() {
// ---------- Solve velocity constraints for joints and contacts ---------- //
// Initialize the contact solver
mContactSolver.init(mIslands, mNbIslands, mTimeStep);
// For each island of the world
for (uint islandIndex = 0; islandIndex < mNbIslands; islandIndex++) {
// Check if there are contacts and constraints to solve
bool isConstraintsToSolve = mIslands[islandIndex]->getNbJoints() > 0;
bool isContactsToSolve = mIslands[islandIndex]->getNbContactManifolds() > 0;
if (!isConstraintsToSolve && !isContactsToSolve) continue;
//bool isContactsToSolve = mIslands[islandIndex]->getNbContactManifolds() > 0;
//if (!isConstraintsToSolve && !isContactsToSolve) continue;
// If there are contacts in the current island
if (isContactsToSolve) {
// if (isContactsToSolve) {
// Initialize the solver
mContactSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]);
// // Initialize the solver
// mContactSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]);
// Warm start the contact solver
mContactSolver.warmStart();
}
// // Warm start the contact solver
// if (mContactSolver.IsWarmStartingActive()) {
// mContactSolver.warmStart();
// }
// }
// If there are constraints
if (isConstraintsToSolve) {
@ -388,26 +371,32 @@ void DynamicsWorld::solveContactsAndConstraints() {
// Initialize the constraint solver
mConstraintSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]);
}
}
// For each iteration of the velocity solver
for (uint i=0; i<mNbVelocitySolverIterations; i++) {
// For each iteration of the velocity solver
for (uint i=0; i<mNbVelocitySolverIterations; i++) {
for (uint islandIndex = 0; islandIndex < mNbIslands; islandIndex++) {
// Solve the constraints
bool isConstraintsToSolve = mIslands[islandIndex]->getNbJoints() > 0;
if (isConstraintsToSolve) {
mConstraintSolver.solveVelocityConstraints(mIslands[islandIndex]);
}
// Solve the contacts
if (isContactsToSolve) mContactSolver.solve();
}
// Cache the lambda values in order to use them in the next
// step and cleanup the contact solver
if (isContactsToSolve) {
mContactSolver.storeImpulses();
mContactSolver.cleanup();
}
mContactSolver.solve();
// Solve the contacts
// if (isContactsToSolve) {
// mContactSolver.resetTotalPenetrationImpulse();
// mContactSolver.solvePenetrationConstraints();
// mContactSolver.solveFrictionConstraints();
// }
}
mContactSolver.storeImpulses();
}
// Solve the position error correction of the constraints
@ -446,7 +435,7 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) {
assert(bodyID < std::numeric_limits<reactphysics3d::bodyindex>::max());
// Create the rigid body
RigidBody* rigidBody = new (mMemoryAllocator.allocate(sizeof(RigidBody))) RigidBody(transform,
RigidBody* rigidBody = new (mPoolAllocator.allocate(sizeof(RigidBody))) RigidBody(transform,
*this, bodyID);
assert(rigidBody != nullptr);
@ -487,7 +476,7 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) {
mRigidBodies.erase(rigidBody);
// Free the object from the memory allocator
mMemoryAllocator.release(rigidBody, sizeof(RigidBody));
mPoolAllocator.release(rigidBody, sizeof(RigidBody));
}
// Create a joint between two bodies in the world and return a pointer to the new joint
@ -505,7 +494,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) {
// Ball-and-Socket joint
case JointType::BALLSOCKETJOINT:
{
void* allocatedMemory = mMemoryAllocator.allocate(sizeof(BallAndSocketJoint));
void* allocatedMemory = mPoolAllocator.allocate(sizeof(BallAndSocketJoint));
const BallAndSocketJointInfo& info = static_cast<const BallAndSocketJointInfo&>(
jointInfo);
newJoint = new (allocatedMemory) BallAndSocketJoint(info);
@ -515,7 +504,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) {
// Slider joint
case JointType::SLIDERJOINT:
{
void* allocatedMemory = mMemoryAllocator.allocate(sizeof(SliderJoint));
void* allocatedMemory = mPoolAllocator.allocate(sizeof(SliderJoint));
const SliderJointInfo& info = static_cast<const SliderJointInfo&>(jointInfo);
newJoint = new (allocatedMemory) SliderJoint(info);
break;
@ -524,7 +513,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) {
// Hinge joint
case JointType::HINGEJOINT:
{
void* allocatedMemory = mMemoryAllocator.allocate(sizeof(HingeJoint));
void* allocatedMemory = mPoolAllocator.allocate(sizeof(HingeJoint));
const HingeJointInfo& info = static_cast<const HingeJointInfo&>(jointInfo);
newJoint = new (allocatedMemory) HingeJoint(info);
break;
@ -533,7 +522,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) {
// Fixed joint
case JointType::FIXEDJOINT:
{
void* allocatedMemory = mMemoryAllocator.allocate(sizeof(FixedJoint));
void* allocatedMemory = mPoolAllocator.allocate(sizeof(FixedJoint));
const FixedJointInfo& info = static_cast<const FixedJointInfo&>(jointInfo);
newJoint = new (allocatedMemory) FixedJoint(info);
break;
@ -586,8 +575,8 @@ void DynamicsWorld::destroyJoint(Joint* joint) {
mJoints.erase(joint);
// Remove the joint from the joint list of the bodies involved in the joint
joint->mBody1->removeJointFromJointsList(mMemoryAllocator, joint);
joint->mBody2->removeJointFromJointsList(mMemoryAllocator, joint);
joint->mBody1->removeJointFromJointsList(mPoolAllocator, joint);
joint->mBody2->removeJointFromJointsList(mPoolAllocator, joint);
size_t nbBytes = joint->getSizeInBytes();
@ -595,7 +584,7 @@ void DynamicsWorld::destroyJoint(Joint* joint) {
joint->~Joint();
// Release the allocated memory
mMemoryAllocator.release(joint, nbBytes);
mPoolAllocator.release(joint, nbBytes);
}
// Add the joint to the list of joints of the two bodies involved in the joint
@ -604,13 +593,13 @@ void DynamicsWorld::addJointToBody(Joint* joint) {
assert(joint != nullptr);
// Add the joint at the beginning of the linked list of joints of the first body
void* allocatedMemory1 = mMemoryAllocator.allocate(sizeof(JointListElement));
void* allocatedMemory1 = mPoolAllocator.allocate(sizeof(JointListElement));
JointListElement* jointListElement1 = new (allocatedMemory1) JointListElement(joint,
joint->mBody1->mJointsList);
joint->mBody1->mJointsList = jointListElement1;
// Add the joint at the beginning of the linked list of joints of the second body
void* allocatedMemory2 = mMemoryAllocator.allocate(sizeof(JointListElement));
void* allocatedMemory2 = mPoolAllocator.allocate(sizeof(JointListElement));
JointListElement* jointListElement2 = new (allocatedMemory2) JointListElement(joint,
joint->mBody2->mJointsList);
joint->mBody2->mJointsList = jointListElement2;
@ -629,24 +618,9 @@ void DynamicsWorld::computeIslands() {
uint nbBodies = mRigidBodies.size();
// Clear all the islands
for (uint i=0; i<mNbIslands; i++) {
// Call the island destructor
mIslands[i]->~Island();
// Release the allocated memory for the island
mMemoryAllocator.release(mIslands[i], sizeof(Island));
}
// Allocate and create the array of islands
if (mNbIslandsCapacity != nbBodies && nbBodies > 0) {
if (mNbIslandsCapacity > 0) {
mMemoryAllocator.release(mIslands, sizeof(Island*) * mNbIslandsCapacity);
}
mNbIslandsCapacity = nbBodies;
mIslands = (Island**)mMemoryAllocator.allocate(sizeof(Island*) * mNbIslandsCapacity);
}
// Allocate and create the array of islands pointer. This memory is allocated
// in the single frame allocator
mIslands = static_cast<Island**>(mSingleFrameAllocator.allocate(sizeof(Island*) * nbBodies));
mNbIslands = 0;
int nbContactManifolds = 0;
@ -662,7 +636,7 @@ void DynamicsWorld::computeIslands() {
// Create a stack (using an array) for the rigid bodies to visit during the Depth First Search
size_t nbBytesStack = sizeof(RigidBody*) * nbBodies;
RigidBody** stackBodiesToVisit = (RigidBody**)mMemoryAllocator.allocate(nbBytesStack);
RigidBody** stackBodiesToVisit = static_cast<RigidBody**>(mSingleFrameAllocator.allocate(nbBytesStack));
// For each rigid body of the world
for (std::set<RigidBody*>::iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) {
@ -685,10 +659,9 @@ void DynamicsWorld::computeIslands() {
body->mIsAlreadyInIsland = true;
// Create the new island
void* allocatedMemoryIsland = mMemoryAllocator.allocate(sizeof(Island));
mIslands[mNbIslands] = new (allocatedMemoryIsland) Island(nbBodies,
nbContactManifolds,
mJoints.size(), mMemoryAllocator);
void* allocatedMemoryIsland = mSingleFrameAllocator.allocate(sizeof(Island));
mIslands[mNbIslands] = new (allocatedMemoryIsland) Island(nbBodies, nbContactManifolds, mJoints.size(),
mSingleFrameAllocator);
// While there are still some bodies to visit in the stack
while (stackIndex > 0) {
@ -778,9 +751,6 @@ void DynamicsWorld::computeIslands() {
mNbIslands++;
}
// Release the allocated memory for the stack of bodies to visit
mMemoryAllocator.release(stackBodiesToVisit, nbBytesStack);
}
// Put bodies to sleep if needed.

View File

@ -50,6 +50,9 @@ class DynamicsWorld : public CollisionWorld {
// -------------------- Attributes -------------------- //
/// Single frame Memory allocator
SingleFrameAllocator mSingleFrameAllocator;
/// Contact solver
ContactSolver mContactSolver;
@ -106,15 +109,9 @@ class DynamicsWorld : public CollisionWorld {
/// Number of islands in the world
uint mNbIslands;
/// Current allocated capacity for the islands
uint mNbIslandsCapacity;
/// Array with all the islands of awaken bodies
Island** mIslands;
/// Current allocated capacity for the bodies
uint mNbBodiesCapacity;
/// Sleep linear velocity threshold
decimal mSleepLinearVelocity;
@ -207,10 +204,6 @@ class DynamicsWorld : public CollisionWorld {
/// Set the position correction technique used for joints
void setJointsPositionCorrectionTechnique(JointsPositionCorrectionTechnique technique);
/// 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);
/// Create a rigid body into the physics world.
RigidBody* createRigidBody(const Transform& transform);
@ -370,16 +363,6 @@ inline void DynamicsWorld::setJointsPositionCorrectionTechnique(
}
}
// Activate or deactivate the solving of friction constraints at the center of
// the contact manifold instead of solving them at each contact point
/**
* @param isActive True if you want the friction to be solved at the center of
* the contact manifold and false otherwise
*/
inline void DynamicsWorld::setIsSolveFrictionAtContactManifoldCenterActive(bool isActive) {
mContactSolver.setIsSolveFrictionAtContactManifoldCenterActive(isActive);
}
// Return the gravity vector of the world
/**
* @return The current gravity vector (in meter per seconds squared)

View File

@ -29,26 +29,18 @@
using namespace reactphysics3d;
// Constructor
Island::Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints,
MemoryAllocator& memoryAllocator)
Island::Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints, SingleFrameAllocator& allocator)
: mBodies(nullptr), mContactManifolds(nullptr), mJoints(nullptr), mNbBodies(0),
mNbContactManifolds(0), mNbJoints(0), mMemoryAllocator(memoryAllocator) {
mNbContactManifolds(0), mNbJoints(0) {
// Allocate memory for the arrays
mNbAllocatedBytesBodies = sizeof(RigidBody*) * nbMaxBodies;
mBodies = (RigidBody**) mMemoryAllocator.allocate(mNbAllocatedBytesBodies);
mNbAllocatedBytesContactManifolds = sizeof(ContactManifold*) * nbMaxContactManifolds;
mContactManifolds = (ContactManifold**) mMemoryAllocator.allocate(
mNbAllocatedBytesContactManifolds);
mNbAllocatedBytesJoints = sizeof(Joint*) * nbMaxJoints;
mJoints = (Joint**) mMemoryAllocator.allocate(mNbAllocatedBytesJoints);
// Allocate memory for the arrays on the single frame allocator
mBodies = static_cast<RigidBody**>(allocator.allocate(sizeof(RigidBody*) * nbMaxBodies));
mContactManifolds = static_cast<ContactManifold**>(allocator.allocate(sizeof(ContactManifold*) * nbMaxContactManifolds));
mJoints = static_cast<Joint**>(allocator.allocate(sizeof(Joint*) * nbMaxJoints));
}
// Destructor
Island::~Island() {
// Release the memory of the arrays
mMemoryAllocator.release(mBodies, mNbAllocatedBytesBodies);
mMemoryAllocator.release(mContactManifolds, mNbAllocatedBytesContactManifolds);
mMemoryAllocator.release(mJoints, mNbAllocatedBytesJoints);
// This destructor is never called because memory is allocated on the
// single frame allocator
}

View File

@ -27,7 +27,7 @@
#define REACTPHYSICS3D_ISLAND_H
// Libraries
#include "memory/MemoryAllocator.h"
#include "memory/SingleFrameAllocator.h"
#include "body/RigidBody.h"
#include "constraint/Joint.h"
#include "collision/ContactManifold.h"
@ -63,25 +63,13 @@ class Island {
/// Current number of joints in the island
uint mNbJoints;
/// Reference to the memory allocator
MemoryAllocator& mMemoryAllocator;
/// Number of bytes allocated for the bodies array
size_t mNbAllocatedBytesBodies;
/// Number of bytes allocated for the contact manifolds array
size_t mNbAllocatedBytesContactManifolds;
/// Number of bytes allocated for the joints array
size_t mNbAllocatedBytesJoints;
public:
// -------------------- Methods -------------------- //
/// Constructor
Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints,
MemoryAllocator& memoryAllocator);
SingleFrameAllocator& allocator);
/// Destructor
~Island();
@ -114,7 +102,7 @@ class Island {
RigidBody** getBodies();
/// Return a pointer to the array of contact manifolds
ContactManifold** getContactManifold();
ContactManifold** getContactManifolds();
/// Return a pointer to the array of joints
Joint** getJoints();
@ -164,7 +152,7 @@ inline RigidBody** Island::getBodies() {
}
// Return a pointer to the array of contact manifolds
inline ContactManifold** Island::getContactManifold() {
inline ContactManifold** Island::getContactManifolds() {
return mContactManifolds;
}

View File

@ -31,7 +31,7 @@ using namespace reactphysics3d;
// Constructor
OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2,
int nbMaxContactManifolds, MemoryAllocator& memoryAllocator)
int nbMaxContactManifolds, PoolAllocator& memoryAllocator)
: mContactManifoldSet(shape1, shape2, memoryAllocator, nbMaxContactManifolds),
mCachedSeparatingAxis(0.0, 1.0, 0.0) {

View File

@ -63,7 +63,7 @@ class OverlappingPair {
/// Constructor
OverlappingPair(ProxyShape* shape1, ProxyShape* shape2,
int nbMaxContactManifolds, MemoryAllocator& memoryAllocator);
int nbMaxContactManifolds, PoolAllocator& memoryAllocator);
/// Destructor
~OverlappingPair() = default;

View File

@ -65,17 +65,17 @@ Vector3 Vector3::getOneUnitOrthogonalVector() const {
assert(length() > MACHINE_EPSILON);
// Get the minimum element of the vector
Vector3 vectorAbs(fabs(x), fabs(y), fabs(z));
Vector3 vectorAbs(std::fabs(x), std::fabs(y), std::fabs(z));
int minElement = vectorAbs.getMinAxis();
if (minElement == 0) {
return Vector3(0.0, -z, y) / sqrt(y*y + z*z);
return Vector3(0.0, -z, y) / std::sqrt(y*y + z*z);
}
else if (minElement == 1) {
return Vector3(-z, 0.0, x) / sqrt(x*x + z*z);
return Vector3(-z, 0.0, x) / std::sqrt(x*x + z*z);
}
else {
return Vector3(-y, x, 0.0) / sqrt(x*x + y*y);
return Vector3(-y, x, 0.0) / std::sqrt(x*x + y*y);
}
}

View File

@ -184,7 +184,7 @@ inline void Vector3::setAllValues(decimal newX, decimal newY, decimal newZ) {
// Return the length of the vector
inline decimal Vector3::length() const {
return sqrt(x*x + y*y + z*z);
return std::sqrt(x*x + y*y + z*z);
}
// Return the square of the length of the vector

View File

@ -24,19 +24,19 @@
********************************************************************************/
// Libraries
#include "MemoryAllocator.h"
#include "PoolAllocator.h"
#include <cstdlib>
#include <cassert>
using namespace reactphysics3d;
// Initialization of static variables
bool MemoryAllocator::isMapSizeToHeadIndexInitialized = false;
size_t MemoryAllocator::mUnitSizes[NB_HEAPS];
int MemoryAllocator::mMapSizeToHeapIndex[MAX_UNIT_SIZE + 1];
bool PoolAllocator::isMapSizeToHeadIndexInitialized = false;
size_t PoolAllocator::mUnitSizes[NB_HEAPS];
int PoolAllocator::mMapSizeToHeapIndex[MAX_UNIT_SIZE + 1];
// Constructor
MemoryAllocator::MemoryAllocator() {
PoolAllocator::PoolAllocator() {
// Allocate some memory to manage the blocks
mNbAllocatedMemoryBlocks = 64;
@ -78,7 +78,7 @@ MemoryAllocator::MemoryAllocator() {
}
// Destructor
MemoryAllocator::~MemoryAllocator() {
PoolAllocator::~PoolAllocator() {
// Release the memory allocated for each block
for (uint i=0; i<mNbCurrentMemoryBlocks; i++) {
@ -96,7 +96,7 @@ MemoryAllocator::~MemoryAllocator() {
// Allocate memory of a given size (in bytes) and return a pointer to the
// allocated memory.
void* MemoryAllocator::allocate(size_t size) {
void* PoolAllocator::allocate(size_t size) {
// We cannot allocate zero bytes
if (size == 0) return nullptr;
@ -164,7 +164,7 @@ void* MemoryAllocator::allocate(size_t size) {
}
// Release previously allocated memory.
void MemoryAllocator::release(void* pointer, size_t size) {
void PoolAllocator::release(void* pointer, size_t size) {
// Cannot release a 0-byte allocated memory
if (size == 0) return;

View File

@ -23,8 +23,8 @@
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_MEMORY_ALLOCATOR_H
#define REACTPHYSICS3D_MEMORY_ALLOCATOR_H
#ifndef REACTPHYSICS3D_POOL_ALLOCATOR_H
#define REACTPHYSICS3D_POOL_ALLOCATOR_H
// Libraries
#include <cstring>
@ -33,14 +33,14 @@
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Class MemoryAllocator
// Class PoolAllocator
/**
* This class is used to efficiently allocate memory on the heap.
* It allows us to allocate small blocks of memory (smaller or equal to 1024 bytes)
* efficiently. This implementation is inspired by the small block allocator
* described here : http://www.codeproject.com/useritems/Small_Block_Allocator.asp
*/
class MemoryAllocator {
class PoolAllocator {
private :
@ -126,10 +126,10 @@ class MemoryAllocator {
// -------------------- Methods -------------------- //
/// Constructor
MemoryAllocator();
PoolAllocator();
/// Destructor
~MemoryAllocator();
~PoolAllocator();
/// Allocate memory of a given size (in bytes) and return a pointer to the
/// allocated memory.

View File

@ -0,0 +1,80 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2016 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
// Libraries
#include "SingleFrameAllocator.h"
#include <cstdlib>
#include <cassert>
using namespace reactphysics3d;
// Constructor
SingleFrameAllocator::SingleFrameAllocator(size_t totalSizeBytes)
: mTotalSizeBytes(totalSizeBytes), mCurrentOffset(0) {
// Allocate a whole block of memory at the beginning
mMemoryBufferStart = static_cast<char*>(malloc(mTotalSizeBytes));
assert(mMemoryBufferStart != nullptr);
}
// Destructor
SingleFrameAllocator::~SingleFrameAllocator() {
// Release the memory allocated at the beginning
free(mMemoryBufferStart);
}
// Allocate memory of a given size (in bytes) and return a pointer to the
// allocated memory.
void* SingleFrameAllocator::allocate(size_t size) {
// Check that there is enough remaining memory in the buffer
if (static_cast<size_t>(mCurrentOffset) + size > mTotalSizeBytes) {
// This should never occur. If it does, you must increase the initial
// size of memory of this allocator
assert(false);
// Return null
return nullptr;
}
// Next available memory location
void* nextAvailableMemory = mMemoryBufferStart + mCurrentOffset;
// Increment the offset
mCurrentOffset += size;
// Return the next available memory location
return nextAvailableMemory;
}
// Reset the marker of the current allocated memory
void SingleFrameAllocator::reset() {
// Reset the current offset at the beginning of the block
mCurrentOffset = 0;
}

View File

@ -23,63 +23,52 @@
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_IMPULSE_H
#define REACTPHYSICS3D_IMPULSE_H
#ifndef REACTPHYSICS3D_SINGLE_FRAME_ALLOCATOR_H
#define REACTPHYSICS3D_SINGLE_FRAME_ALLOCATOR_H
// Libraries
#include "mathematics/mathematics.h"
#include <cstring>
#include "configuration.h"
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Structure Impulse
// Class SingleFrameAllocator
/**
* Represents an impulse that we can apply to bodies in the contact or constraint solver.
* This class represent a memory allocator used to efficiently allocate
* memory on the heap that is used during a single frame.
*/
struct Impulse {
class SingleFrameAllocator {
private:
// -------------------- Methods -------------------- //
public:
private :
// -------------------- Attributes -------------------- //
/// Linear impulse applied to the first body
const Vector3 linearImpulseBody1;
/// Total size (in bytes) of memory of the allocator
size_t mTotalSizeBytes;
/// Angular impulse applied to the first body
const Vector3 angularImpulseBody1;
/// Pointer to the beginning of the allocated memory block
char* mMemoryBufferStart;
/// Linear impulse applied to the second body
const Vector3 linearImpulseBody2;
/// Pointer to the next available memory location in the buffer
int mCurrentOffset;
/// Angular impulse applied to the second body
const Vector3 angularImpulseBody2;
public :
// -------------------- Methods -------------------- //
/// Constructor
Impulse(const Vector3& initLinearImpulseBody1, const Vector3& initAngularImpulseBody1,
const Vector3& initLinearImpulseBody2, const Vector3& initAngularImpulseBody2)
: linearImpulseBody1(initLinearImpulseBody1),
angularImpulseBody1(initAngularImpulseBody1),
linearImpulseBody2(initLinearImpulseBody2),
angularImpulseBody2(initAngularImpulseBody2) {
SingleFrameAllocator(size_t totalSizeBytes);
}
/// Destructor
~SingleFrameAllocator();
/// Copy-constructor
Impulse(const Impulse& impulse)
: linearImpulseBody1(impulse.linearImpulseBody1),
angularImpulseBody1(impulse.angularImpulseBody1),
linearImpulseBody2(impulse.linearImpulseBody2),
angularImpulseBody2(impulse.angularImpulseBody2) {
/// Allocate memory of a given size (in bytes)
void* allocate(size_t size);
}
/// Reset the marker of the current allocated memory
void reset();
/// Deleted assignment operator
Impulse& operator=(const Impulse& impulse) = delete;
};
}