Add WorldSettings class for world configuration settings

This commit is contained in:
Daniel Chappuis 2018-03-04 19:10:32 +01:00
parent 0f4d41e8fc
commit cd2bc9665e
22 changed files with 134 additions and 104 deletions

View File

@ -41,7 +41,7 @@ using namespace reactphysics3d;
RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyindex id)
: CollisionBody(transform, world, id), mArrayIndex(0), mInitMass(decimal(1.0)),
mCenterOfMassLocal(0, 0, 0), mCenterOfMassWorld(transform.getPosition()),
mIsGravityEnabled(true), mLinearDamping(decimal(0.0)), mAngularDamping(decimal(0.0)),
mIsGravityEnabled(true), mMaterial(world.mConfig), mLinearDamping(decimal(0.0)), mAngularDamping(decimal(0.0)),
mJointsList(nullptr), mIsCenterOfMassSetByUser(false), mIsInertiaTensorSetByUser(false) {
// Compute the inverse mass

View File

@ -325,7 +325,7 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro
// Create the overlapping pair and add it into the set of overlapping pairs
OverlappingPair* newPair = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool, sizeof(OverlappingPair)))
OverlappingPair(shape1, shape2, mMemoryManager.getPoolAllocator(),
mMemoryManager.getSingleFrameAllocator());
mMemoryManager.getSingleFrameAllocator(), mWorld->mConfig);
assert(newPair != nullptr);
mOverlappingPairs.add(Pair<Pair<uint, uint>, OverlappingPair*>(pairID, newPair));
@ -570,7 +570,7 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2)
// Create a temporary overlapping pair
OverlappingPair pair(body1ProxyShape, body2ProxyShape, mMemoryManager.getPoolAllocator(),
mMemoryManager.getPoolAllocator());
mMemoryManager.getPoolAllocator(), mWorld->mConfig);
// Compute the middle-phase collision detection between the two shapes
NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair);
@ -666,7 +666,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl
// Create a temporary overlapping pair
OverlappingPair pair(bodyProxyShape, proxyShape, mMemoryManager.getPoolAllocator(),
mMemoryManager.getPoolAllocator());
mMemoryManager.getPoolAllocator(), mWorld->mConfig);
// Compute the middle-phase collision detection between the two shapes
NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair);
@ -751,7 +751,7 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body
// Create a temporary overlapping pair
OverlappingPair pair(body1ProxyShape, body2ProxyShape, mMemoryManager.getPoolAllocator(),
mMemoryManager.getPoolAllocator());
mMemoryManager.getPoolAllocator(), mWorld->mConfig);
// Compute the middle-phase collision detection between the two shapes
NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair);
@ -844,7 +844,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c
// Create a temporary overlapping pair
OverlappingPair pair(bodyProxyShape, proxyShape, mMemoryManager.getPoolAllocator(),
mMemoryManager.getPoolAllocator());
mMemoryManager.getPoolAllocator(), mWorld->mConfig);
// Compute the middle-phase collision detection between the two shapes
NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair);
@ -919,7 +919,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) {
// Create a new overlapping pair so that we do not work on the original one
OverlappingPair pair(originalPair->getShape1(), originalPair->getShape2(), mMemoryManager.getPoolAllocator(),
mMemoryManager.getPoolAllocator());
mMemoryManager.getPoolAllocator(), mWorld->mConfig);
ProxyShape* shape1 = pair.getShape1();
ProxyShape* shape2 = pair.getShape2();

View File

@ -30,11 +30,13 @@
using namespace reactphysics3d;
// Constructor
ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, MemoryAllocator& memoryAllocator)
ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2,
MemoryAllocator& memoryAllocator, const WorldSettings& worldSettings)
: mShape1(shape1), mShape2(shape2), mContactPoints(nullptr),
mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0),
mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false),
mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObsolete(false) {
mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObsolete(false),
mWorldSettings(worldSettings) {
// For each contact point info in the manifold
const ContactPointInfo* pointInfo = manifoldInfo->getFirstContactPointInfo();
@ -102,7 +104,7 @@ void ContactManifold::addContactPoint(const ContactPointInfo* contactPointInfo)
assert(contactPointInfo != nullptr);
// Create the new contact point
ContactPoint* contactPoint = new (mMemoryAllocator.allocate(sizeof(ContactPoint))) ContactPoint(contactPointInfo);
ContactPoint* contactPoint = new (mMemoryAllocator.allocate(sizeof(ContactPoint))) ContactPoint(contactPointInfo, mWorldSettings);
// Add the new contact point into the manifold
contactPoint->setNext(mContactPoints);

View File

@ -139,6 +139,9 @@ class ContactManifold {
/// True if the contact manifold is obsolete
bool mIsObsolete;
/// World settings
const WorldSettings& mWorldSettings;
// -------------------- Methods -------------------- //
/// Return true if the contact manifold has already been added into an island
@ -216,7 +219,7 @@ class ContactManifold {
/// Constructor
ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2,
MemoryAllocator& memoryAllocator);
MemoryAllocator& memoryAllocator, const WorldSettings& worldSettings);
/// Destructor
~ContactManifold();

View File

@ -30,9 +30,9 @@ using namespace reactphysics3d;
// Constructor
ContactManifoldSet::ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2,
MemoryAllocator& memoryAllocator)
MemoryAllocator& memoryAllocator, const WorldSettings& worldSettings)
: mNbManifolds(0), mShape1(shape1),
mShape2(shape2), mMemoryAllocator(memoryAllocator), mManifolds(nullptr) {
mShape2(shape2), mMemoryAllocator(memoryAllocator), mManifolds(nullptr), mWorldSettings(worldSettings) {
// Compute the maximum number of manifolds allowed between the two shapes
mNbMaxManifolds = computeNbMaxContactManifolds(shape1->getCollisionShape(), shape2->getCollisionShape());
@ -157,7 +157,7 @@ ContactManifold* ContactManifoldSet::selectManifoldWithSimilarNormal(const Conta
assert(point != nullptr);
// If the contact normal of the two manifolds are close enough
if (contactPoint->normal.dot(point->getNormal()) >= COS_ANGLE_SIMILAR_CONTACT_MANIFOLD) {
if (contactPoint->normal.dot(point->getNormal()) >= mWorldSettings.cosAngleSimilarContactManifold) {
return manifold;
}
@ -191,7 +191,7 @@ void ContactManifoldSet::clear() {
void ContactManifoldSet::createManifold(const ContactManifoldInfo* manifoldInfo) {
ContactManifold* manifold = new (mMemoryAllocator.allocate(sizeof(ContactManifold)))
ContactManifold(manifoldInfo, mShape1, mShape2, mMemoryAllocator);
ContactManifold(manifoldInfo, mShape1, mShape2, mMemoryAllocator, mWorldSettings);
manifold->setPrevious(nullptr);
manifold->setNext(mManifolds);
if (mManifolds != nullptr) {

View File

@ -66,6 +66,9 @@ class ContactManifoldSet {
/// Contact manifolds of the set
ContactManifold* mManifolds;
/// World settings
const WorldSettings& mWorldSettings;
// -------------------- Methods -------------------- //
/// Create a new contact manifold and add it to the set
@ -95,7 +98,7 @@ class ContactManifoldSet {
/// Constructor
ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2,
MemoryAllocator& memoryAllocator);
MemoryAllocator& memoryAllocator, const WorldSettings& worldSettings);
/// Destructor
~ContactManifoldSet();
@ -167,11 +170,11 @@ inline int ContactManifoldSet::computeNbMaxContactManifolds(const CollisionShape
// If both shapes are convex
if (shape1->isConvex() && shape2->isConvex()) {
return NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE;
return mWorldSettings.nbMaxContactManifoldsConvexShape;
} // If there is at least one concave shape
else {
return NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE;
return mWorldSettings.nbMaxContactManifoldsConcaveShape;
}
}

View File

@ -94,41 +94,6 @@ constexpr decimal PI = decimal(3.14159265);
/// 2*Pi constant
constexpr decimal PI_TIMES_2 = decimal(6.28318530);
/// Default friction coefficient for a rigid body
constexpr decimal DEFAULT_FRICTION_COEFFICIENT = decimal(0.3);
/// Default bounciness factor for a rigid body
constexpr decimal DEFAULT_BOUNCINESS = decimal(0.5);
/// Default rolling resistance
constexpr decimal DEFAULT_ROLLING_RESISTANCE = decimal(0.0);
/// True if the sleeping technique is enabled
constexpr bool SLEEPING_ENABLED = true;
/// Distance threshold for two contact points for a valid persistent contact (in meters)
constexpr decimal PERSISTENT_CONTACT_DIST_THRESHOLD = decimal(0.03);
/// Velocity threshold for contact velocity restitution
constexpr decimal RESTITUTION_VELOCITY_THRESHOLD = decimal(1.0);
/// Number of iterations when solving the velocity constraints of the Sequential Impulse technique
constexpr uint DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS = 10;
/// Number of iterations when solving the position constraints of the Sequential Impulse technique
constexpr uint DEFAULT_POSITION_SOLVER_NB_ITERATIONS = 5;
/// Time (in seconds) that a body must stay still to be considered sleeping
constexpr float DEFAULT_TIME_BEFORE_SLEEP = 1.0f;
/// A body with a linear velocity smaller than the sleep linear velocity (in m/s)
/// might enter sleeping mode.
constexpr decimal DEFAULT_SLEEP_LINEAR_VELOCITY = decimal(0.02);
/// A body with angular velocity smaller than the sleep angular velocity (in rad/s)
/// might enter sleeping mode
constexpr decimal DEFAULT_SLEEP_ANGULAR_VELOCITY = decimal(3.0 * (PI / 180.0));
/// In the broad-phase collision detection (dynamic AABB tree), the AABBs are
/// inflated with a constant gap to allow the collision shape to move a little bit
/// without triggering a large modification of the tree which can be costly
@ -139,21 +104,60 @@ constexpr decimal DYNAMIC_TREE_AABB_GAP = decimal(0.1);
/// followin constant with the linear velocity and the elapsed time between two frames.
constexpr decimal DYNAMIC_TREE_AABB_LIN_GAP_MULTIPLIER = decimal(1.7);
/// Maximum number of contact manifolds in an overlapping pair that involves two
/// convex collision shapes.
constexpr int NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE = 1;
/// Structure WorldSettings
/**
* This class is used to describe some settings of a physics world.
*/
struct WorldSettings {
/// Maximum number of contact manifolds in an overlapping pair that involves at
/// least one concave collision shape.
constexpr int NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE = 3;
/// Distance threshold for two contact points for a valid persistent contact (in meters)
decimal persistentContactDistanceThreshold = decimal(0.03);
/// This is used to test if two contact manifold are similar (same contact normal) in order to
/// merge them. If the cosine of the angle between the normals of the two manifold are larger
/// than the value bellow, the manifold are considered to be similar.
constexpr decimal COS_ANGLE_SIMILAR_CONTACT_MANIFOLD = decimal(0.95);
/// Default friction coefficient for a rigid body
decimal defaultFrictionCoefficient = decimal(0.3);
/// Size (in bytes) of the single frame allocator
constexpr std::size_t INIT_SINGLE_FRAME_ALLOCATOR_BYTES = 1048576; // 1Mb
/// Default bounciness factor for a rigid body
decimal defaultBounciness = decimal(0.5);
/// Velocity threshold for contact velocity restitution
decimal restitutionVelocityThreshold = decimal(1.0);
/// Default rolling resistance
decimal defaultRollingRestistance = decimal(0.0);
/// True if the sleeping technique is enabled
bool isSleepingEnabled = true;
/// Number of iterations when solving the velocity constraints of the Sequential Impulse technique
uint defaultVelocitySolverNbIterations = 10;
/// Number of iterations when solving the position constraints of the Sequential Impulse technique
uint defaultPositionSolverNbIterations = 5;
/// Time (in seconds) that a body must stay still to be considered sleeping
float defaultTimeBeforeSleep = 1.0f;
/// A body with a linear velocity smaller than the sleep linear velocity (in m/s)
/// might enter sleeping mode.
decimal defaultSleepLinearVelocity = decimal(0.02);
/// A body with angular velocity smaller than the sleep angular velocity (in rad/s)
/// might enter sleeping mode
decimal defaultSleepAngularVelocity = decimal(3.0) * (PI / decimal(180.0));
/// Maximum number of contact manifolds in an overlapping pair that involves two
/// convex collision shapes.
int nbMaxContactManifoldsConvexShape = 1;
/// Maximum number of contact manifolds in an overlapping pair that involves at
/// least one concave collision shape.
int nbMaxContactManifoldsConcaveShape = 3;
/// This is used to test if two contact manifold are similar (same contact normal) in order to
/// merge them. If the cosine of the angle between the normals of the two manifold are larger
/// than the value bellow, the manifold are considered to be similar.
decimal cosAngleSimilarContactManifold = decimal(0.95);
};
}

View File

@ -31,12 +31,13 @@ using namespace reactphysics3d;
using namespace std;
// Constructor
ContactPoint::ContactPoint(const ContactPointInfo* contactInfo)
ContactPoint::ContactPoint(const ContactPointInfo* contactInfo, const WorldSettings& worldSettings)
: mNormal(contactInfo->normal),
mPenetrationDepth(contactInfo->penetrationDepth),
mLocalPointOnShape1(contactInfo->localPoint1),
mLocalPointOnShape2(contactInfo->localPoint2),
mIsRestingContact(false), mIsObsolete(false), mNext(nullptr), mPrevious(nullptr) {
mIsRestingContact(false), mIsObsolete(false), mNext(nullptr), mPrevious(nullptr),
mWorldSettings(worldSettings) {
assert(mPenetrationDepth > decimal(0.0));
assert(mNormal.lengthSquare() > decimal(0.8));

View File

@ -75,6 +75,9 @@ class ContactPoint {
/// Pointer to the previous contact point in the double linked-list
ContactPoint* mPrevious;
/// World settings
const WorldSettings& mWorldSettings;
// -------------------- Methods -------------------- //
/// Update the contact point with a new one that is similar (very close)
@ -107,7 +110,7 @@ class ContactPoint {
// -------------------- Methods -------------------- //
/// Constructor
ContactPoint(const ContactPointInfo* contactInfo);
ContactPoint(const ContactPointInfo* contactInfo, const WorldSettings& worldSettings);
/// Destructor
~ContactPoint() = default;
@ -173,8 +176,8 @@ inline decimal ContactPoint::getPenetrationImpulse() const {
// Return true if the contact point is similar (close enougth) to another given contact point
inline bool ContactPoint::isSimilarWithContactPoint(const ContactPointInfo* localContactPointBody1) const {
return (localContactPointBody1->localPoint1 - mLocalPointOnShape1).lengthSquare() <= (PERSISTENT_CONTACT_DIST_THRESHOLD *
PERSISTENT_CONTACT_DIST_THRESHOLD);
return (localContactPointBody1->localPoint1 - mLocalPointOnShape1).lengthSquare() <= (mWorldSettings.persistentContactDistanceThreshold *
mWorldSettings.persistentContactDistanceThreshold);
}
// Set the cached penetration impulse

View File

@ -32,8 +32,8 @@ using namespace reactphysics3d;
using namespace std;
// Constructor
CollisionWorld::CollisionWorld()
: mCollisionDetection(this, mMemoryManager), mBodies(mMemoryManager.getPoolAllocator()), mCurrentBodyID(0),
CollisionWorld::CollisionWorld(const WorldSettings& worldSettings)
: mConfig(worldSettings), mCollisionDetection(this, mMemoryManager), mBodies(mMemoryManager.getPoolAllocator()), mCurrentBodyID(0),
mFreeBodiesIDs(mMemoryManager.getPoolAllocator()), mEventListener(nullptr) {
#ifdef IS_PROFILING_ACTIVE

View File

@ -62,6 +62,9 @@ class CollisionWorld {
/// Memory manager
MemoryManager mMemoryManager;
/// Configuration of the physics world
WorldSettings mConfig;
/// Reference to the collision detection
CollisionDetection mCollisionDetection;
@ -96,7 +99,7 @@ class CollisionWorld {
// -------------------- Methods -------------------- //
/// Constructor
CollisionWorld();
CollisionWorld(const WorldSettings& worldSettings = WorldSettings());
/// Destructor
virtual ~CollisionWorld();

View File

@ -39,11 +39,11 @@ const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2);
const decimal ContactSolver::SLOP = decimal(0.01);
// Constructor
ContactSolver::ContactSolver(MemoryManager& memoryManager)
ContactSolver::ContactSolver(MemoryManager& memoryManager, const WorldSettings& worldSettings)
:mMemoryManager(memoryManager), mSplitLinearVelocities(nullptr),
mSplitAngularVelocities(nullptr), mContactConstraints(nullptr),
mLinearVelocities(nullptr), mAngularVelocities(nullptr),
mIsSplitImpulseActive(true) {
mIsSplitImpulseActive(true), mWorldSettings(worldSettings) {
}
@ -225,7 +225,7 @@ void ContactSolver::initializeForIsland(Island* island) {
deltaV.y * mContactPoints[mNbContactPoints].normal.y +
deltaV.z * mContactPoints[mNbContactPoints].normal.z;
const decimal restitutionFactor = computeMixedRestitutionFactor(body1, body2);
if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) {
if (deltaVDotN < -mWorldSettings.restitutionVelocityThreshold) {
mContactPoints[mNbContactPoints].restitutionBias = restitutionFactor * deltaVDotN;
}

View File

@ -304,6 +304,9 @@ class ContactSolver {
/// True if the split impulse position correction is active
bool mIsSplitImpulseActive;
/// World settings
const WorldSettings& mWorldSettings;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
@ -338,7 +341,7 @@ class ContactSolver {
// -------------------- Methods -------------------- //
/// Constructor
ContactSolver(MemoryManager& memoryManager);
ContactSolver(MemoryManager& memoryManager, const WorldSettings& worldSettings);
/// Destructor
~ContactSolver() = default;

View File

@ -39,20 +39,20 @@ using namespace std;
/**
* @param gravity Gravity vector in the world (in meters per second squared)
*/
DynamicsWorld::DynamicsWorld(const Vector3 &gravity)
: CollisionWorld(),
mContactSolver(mMemoryManager),
mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS),
mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS),
mIsSleepingEnabled(SLEEPING_ENABLED), mRigidBodies(mMemoryManager.getPoolAllocator()),
DynamicsWorld::DynamicsWorld(const Vector3 &gravity, const WorldSettings& worldSettings)
: CollisionWorld(worldSettings),
mContactSolver(mMemoryManager, mConfig),
mNbVelocitySolverIterations(mConfig.defaultVelocitySolverNbIterations),
mNbPositionSolverIterations(mConfig.defaultPositionSolverNbIterations),
mIsSleepingEnabled(mConfig.isSleepingEnabled), mRigidBodies(mMemoryManager.getPoolAllocator()),
mJoints(mMemoryManager.getPoolAllocator()), mGravity(gravity), mTimeStep(decimal(1.0f / 60.0f)),
mIsGravityEnabled(true), mConstrainedLinearVelocities(nullptr),
mConstrainedAngularVelocities(nullptr), mSplitLinearVelocities(nullptr),
mSplitAngularVelocities(nullptr), mConstrainedPositions(nullptr),
mConstrainedOrientations(nullptr), mNbIslands(0), mIslands(nullptr),
mSleepLinearVelocity(DEFAULT_SLEEP_LINEAR_VELOCITY),
mSleepAngularVelocity(DEFAULT_SLEEP_ANGULAR_VELOCITY),
mTimeBeforeSleep(DEFAULT_TIME_BEFORE_SLEEP) {
mSleepLinearVelocity(mConfig.defaultSleepLinearVelocity),
mSleepAngularVelocity(mConfig.defaultSleepAngularVelocity),
mTimeBeforeSleep(mConfig.defaultTimeBeforeSleep) {
#ifdef IS_PROFILING_ACTIVE

View File

@ -153,7 +153,7 @@ class DynamicsWorld : public CollisionWorld {
// -------------------- Methods -------------------- //
/// Constructor
DynamicsWorld(const Vector3& mGravity);
DynamicsWorld(const Vector3& mGravity, const WorldSettings& worldSettings = WorldSettings());
/// Destructor
virtual ~DynamicsWorld() override;

View File

@ -29,10 +29,10 @@
using namespace reactphysics3d;
// Constructor
Material::Material()
: mFrictionCoefficient(DEFAULT_FRICTION_COEFFICIENT),
mRollingResistance(DEFAULT_ROLLING_RESISTANCE),
mBounciness(DEFAULT_BOUNCINESS) {
Material::Material(const WorldSettings& worldSettings)
: mFrictionCoefficient(worldSettings.defaultFrictionCoefficient),
mRollingResistance(worldSettings.defaultRollingRestistance),
mBounciness(worldSettings.defaultBounciness) {
}

View File

@ -58,7 +58,7 @@ class Material {
// -------------------- Methods -------------------- //
/// Constructor
Material();
Material(const WorldSettings& worldSettings);
/// Copy-constructor
Material(const Material& material);

View File

@ -35,10 +35,11 @@ using namespace reactphysics3d;
// Constructor
OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2,
MemoryAllocator& persistentMemoryAllocator, MemoryAllocator& temporaryMemoryAllocator)
: mContactManifoldSet(shape1, shape2, persistentMemoryAllocator), mPotentialContactManifolds(nullptr),
MemoryAllocator& persistentMemoryAllocator, MemoryAllocator& temporaryMemoryAllocator,
const WorldSettings& worldSettings)
: mContactManifoldSet(shape1, shape2, persistentMemoryAllocator, worldSettings), mPotentialContactManifolds(nullptr),
mPersistentAllocator(persistentMemoryAllocator), mTempMemoryAllocator(temporaryMemoryAllocator),
mLastFrameCollisionInfos(mPersistentAllocator) {
mLastFrameCollisionInfos(mPersistentAllocator), mWorldSettings(worldSettings) {
}
@ -80,7 +81,7 @@ void OverlappingPair::addPotentialContactPoints(NarrowPhaseInfo* narrowPhaseInfo
// If we have found a corresponding manifold for the new contact point
// (a manifold with a similar contact normal direction)
if (point->normal.dot(contactPoint->normal) >= COS_ANGLE_SIMILAR_CONTACT_MANIFOLD) {
if (point->normal.dot(contactPoint->normal) >= mWorldSettings.cosAngleSimilarContactManifold) {
// Add the contact point to the manifold
manifold->addContactPoint(contactPoint);

View File

@ -122,13 +122,16 @@ class OverlappingPair {
/// shape Ids of the two collision shapes.
Map<ShapeIdPair, LastFrameCollisionInfo*> mLastFrameCollisionInfos;
/// World settings
const WorldSettings& mWorldSettings;
public:
// -------------------- Methods -------------------- //
/// Constructor
OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, MemoryAllocator& persistentMemoryAllocator,
MemoryAllocator& temporaryMemoryAllocator);
MemoryAllocator& temporaryMemoryAllocator, const WorldSettings& worldSettings);
/// Destructor
~OverlappingPair();

View File

@ -33,7 +33,7 @@ using namespace reactphysics3d;
// Constructor
SingleFrameAllocator::SingleFrameAllocator()
: mTotalSizeBytes(INIT_SINGLE_FRAME_ALLOCATOR_BYTES),
: mTotalSizeBytes(INIT_SINGLE_FRAME_ALLOCATOR_NB_BYTES),
mCurrentOffset(0), mNbFramesTooMuchAllocated(0), mNeedToAllocatedMore(false) {
// Allocate a whole block of memory at the beginning

View File

@ -48,6 +48,9 @@ class SingleFrameAllocator : public MemoryAllocator {
/// memory if too much is allocated
static const int NB_FRAMES_UNTIL_SHRINK = 120;
/// Initial size (in bytes) of the single frame allocator
size_t INIT_SINGLE_FRAME_ALLOCATOR_NB_BYTES = 1048576; // 1Mb
// -------------------- Attributes -------------------- //
/// Total size (in bytes) of memory of the allocator

View File

@ -72,13 +72,14 @@ struct EngineSettings {
EngineSettings defaultSettings;
rp3d::WorldSettings worldSettings;
defaultSettings.timeStep = 1.0f / 60.0f;
defaultSettings.nbVelocitySolverIterations = rp3d::DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS;
defaultSettings.nbPositionSolverIterations = rp3d::DEFAULT_POSITION_SOLVER_NB_ITERATIONS;
defaultSettings.isSleepingEnabled = rp3d::SLEEPING_ENABLED;
defaultSettings.timeBeforeSleep = rp3d::DEFAULT_TIME_BEFORE_SLEEP;
defaultSettings.sleepLinearVelocity = rp3d::DEFAULT_SLEEP_LINEAR_VELOCITY;
defaultSettings.sleepAngularVelocity = rp3d::DEFAULT_SLEEP_ANGULAR_VELOCITY;
defaultSettings.nbVelocitySolverIterations = worldSettings.defaultVelocitySolverNbIterations;
defaultSettings.nbPositionSolverIterations = worldSettings.defaultPositionSolverNbIterations;
defaultSettings.isSleepingEnabled = worldSettings.isSleepingEnabled;
defaultSettings.timeBeforeSleep = worldSettings.defaultTimeBeforeSleep;
defaultSettings.sleepLinearVelocity = worldSettings.defaultSleepLinearVelocity;
defaultSettings.sleepAngularVelocity = worldSettings.defaultSleepAngularVelocity;
defaultSettings.isGravityEnabled = true;
return defaultSettings;