Rename DynamicsWorld class to PhysicsWorld

This commit is contained in:
Daniel Chappuis 2020-01-27 17:46:00 +01:00
parent b0fde22678
commit d36edcdb6e
90 changed files with 1621 additions and 1851 deletions

View File

@ -127,7 +127,6 @@ SET (REACTPHYSICS3D_HEADERS
"src/constraint/SliderJoint.h"
"src/engine/Entity.h"
"src/engine/EntityManager.h"
"src/engine/CollisionWorld.h"
"src/engine/PhysicsCommon.h"
"src/systems/ConstraintSolverSystem.h"
"src/systems/ContactSolverSystem.h"
@ -137,7 +136,7 @@ SET (REACTPHYSICS3D_HEADERS
"src/systems/SolveFixedJointSystem.h"
"src/systems/SolveHingeJointSystem.h"
"src/systems/SolveSliderJointSystem.h"
"src/engine/DynamicsWorld.h"
"src/engine/PhysicsWorld.h"
"src/engine/EventListener.h"
"src/engine/Island.h"
"src/engine/Islands.h"
@ -229,7 +228,6 @@ SET (REACTPHYSICS3D_SOURCES
"src/constraint/HingeJoint.cpp"
"src/constraint/Joint.cpp"
"src/constraint/SliderJoint.cpp"
"src/engine/CollisionWorld.cpp"
"src/engine/PhysicsCommon.cpp"
"src/systems/ConstraintSolverSystem.cpp"
"src/systems/ContactSolverSystem.cpp"
@ -239,7 +237,7 @@ SET (REACTPHYSICS3D_SOURCES
"src/systems/SolveFixedJointSystem.cpp"
"src/systems/SolveHingeJointSystem.cpp"
"src/systems/SolveSliderJointSystem.cpp"
"src/engine/DynamicsWorld.cpp"
"src/engine/PhysicsWorld.cpp"
"src/engine/Island.cpp"
"src/engine/Material.cpp"
"src/engine/OverlappingPairs.cpp"

View File

@ -25,7 +25,7 @@
// Libraries
#include "CollisionBody.h"
#include "engine/CollisionWorld.h"
#include "engine/PhysicsWorld.h"
#include "collision/ContactManifold.h"
#include "collision/RaycastInfo.h"
#include "utils/Logger.h"
@ -39,7 +39,7 @@ using namespace reactphysics3d;
* @param world The physics world where the body is created
* @param id ID of the body
*/
CollisionBody::CollisionBody(CollisionWorld& world, Entity entity)
CollisionBody::CollisionBody(PhysicsWorld& world, Entity entity)
: mEntity(entity), mWorld(world) {
#ifdef IS_LOGGING_ACTIVE

View File

@ -39,8 +39,8 @@ namespace reactphysics3d {
// Declarations
struct ContactManifoldListElement;
class Collider;
class CollisionWorld;
class CollisionShape;
class PhysicsWorld;
struct RaycastInfo;
class DefaultPoolAllocator;
class Profiler;
@ -61,7 +61,7 @@ class CollisionBody {
Entity mEntity;
/// Reference to the world the body belongs to
CollisionWorld& mWorld;
PhysicsWorld& mWorld;
#ifdef IS_LOGGING_ACTIVE
@ -93,7 +93,7 @@ class CollisionBody {
// -------------------- Methods -------------------- //
/// Constructor
CollisionBody(CollisionWorld& world, Entity entity);
CollisionBody(PhysicsWorld& world, Entity entity);
/// Destructor
virtual ~CollisionBody();
@ -179,8 +179,7 @@ class CollisionBody {
// -------------------- Friendship -------------------- //
friend class CollisionWorld;
friend class DynamicsWorld;
friend class PhysicsWorld;
friend class CollisionDetectionSystem;
friend class BroadPhaseAlgorithm;
friend class ConvexMeshShape;

View File

@ -25,9 +25,8 @@
// Libraries
#include "RigidBody.h"
#include "constraint/Joint.h"
#include "collision/shapes/CollisionShape.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
#include "utils/Profiler.h"
// We want to use the ReactPhysics3D namespace
@ -39,8 +38,9 @@ using namespace reactphysics3d;
* @param world The world where the body has been added
* @param id The ID of the body
*/
RigidBody::RigidBody(CollisionWorld& world, Entity entity)
: CollisionBody(world, entity), mMaterial(world.mConfig),
RigidBody::RigidBody(PhysicsWorld& world, Entity entity)
: CollisionBody(world, entity),
mMaterial(world.mConfig.defaultFrictionCoefficient, world.mConfig.defaultRollingRestistance, world.mConfig.defaultBounciness),
mIsCenterOfMassSetByUser(false), mIsInertiaTensorSetByUser(false) {
}
@ -147,7 +147,7 @@ decimal RigidBody::getMass() const {
/// generate some torque and therefore, change the angular velocity of the body.
/// If the body is sleeping, calling this method will wake it up. Note that the
/// force will we added to the sum of the applied forces and that this sum will be
/// reset to zero at the end of each call of the DynamicsWorld::update() method.
/// reset to zero at the end of each call of the PhyscisWorld::update() method.
/// You can only apply a force to a dynamic body otherwise, this method will do nothing.
/**
* @param force The force to apply on the body
@ -197,7 +197,7 @@ void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) {
// Apply an external force to the body at its center of mass.
/// If the body is sleeping, calling this method will wake it up. Note that the
/// force will we added to the sum of the applied forces and that this sum will be
/// reset to zero at the end of each call of the DynamicsWorld::update() method.
/// reset to zero at the end of each call of the PhyscisWorld::update() method.
/// You can only apply a force to a dynamic body otherwise, this method will do nothing.
/**
* @param force The external force to apply on the center of mass of the body
@ -632,7 +632,7 @@ bool RigidBody::isGravityEnabled() const {
// Apply an external torque to the body.
/// If the body is sleeping, calling this method will wake it up. Note that the
/// force will we added to the sum of the applied torques and that this sum will be
/// reset to zero at the end of each call of the DynamicsWorld::update() method.
/// reset to zero at the end of each call of the PhyscisWorld::update() method.
/// You can only apply a force to a dynamic body otherwise, this method will do nothing.
/**
* @param torque The external torque to apply on the body
@ -713,7 +713,7 @@ void RigidBody::updateOverlappingPairs() {
}
/// Return the inverse of the inertia tensor in world coordinates.
const Matrix3x3 RigidBody::getInertiaTensorInverseWorld(CollisionWorld& world, Entity bodyEntity) {
const Matrix3x3 RigidBody::getInertiaTensorInverseWorld(PhysicsWorld& world, Entity bodyEntity) {
Matrix3x3 orientation = world.mTransformComponents.getTransform(bodyEntity).getOrientation().getMatrix();
const Matrix3x3& inverseInertiaLocalTensor = world.mRigidBodyComponents.getInertiaTensorLocalInverse(bodyEntity);

View File

@ -37,8 +37,7 @@ namespace reactphysics3d {
// Class declarations
struct JointListElement;
class Joint;
class DynamicsWorld;
class PhysicsWorld;
class MemoryManager;
enum class BodyType;
@ -77,14 +76,14 @@ class RigidBody : public CollisionBody {
void updateOverlappingPairs();
/// Return the inverse of the inertia tensor in world coordinates.
static const Matrix3x3 getInertiaTensorInverseWorld(CollisionWorld& world, Entity bodyEntity);
static const Matrix3x3 getInertiaTensorInverseWorld(PhysicsWorld& world, Entity bodyEntity);
public :
// -------------------- Methods -------------------- //
/// Constructor
RigidBody(CollisionWorld& world, Entity entity);
RigidBody(PhysicsWorld& world, Entity entity);
/// Destructor
virtual ~RigidBody() override = default;
@ -203,10 +202,9 @@ class RigidBody : public CollisionBody {
// -------------------- Friendship -------------------- //
friend class DynamicsWorld;
friend class PhysicsWorld;
friend class ContactSolverSystem;
friend class DynamicsSystem;
friend class Joint;
friend class BallAndSocketJoint;
friend class SliderJoint;
friend class HingeJoint;
@ -215,6 +213,7 @@ class RigidBody : public CollisionBody {
friend class SolveFixedJointSystem;
friend class SolveHingeJointSystem;
friend class SolveSliderJointSystem;
friend class Joint;
};
// Return a reference to the material properties of the rigid body

View File

@ -28,7 +28,7 @@
#include "utils/Logger.h"
#include "collision/RaycastInfo.h"
#include "memory/MemoryManager.h"
#include "engine/CollisionWorld.h"
#include "engine/PhysicsWorld.h"
using namespace reactphysics3d;

View File

@ -172,8 +172,7 @@ class Collider {
friend class BroadPhaseAlgorithm;
friend class DynamicAABBTree;
friend class CollisionDetectionSystem;
friend class CollisionWorld;
friend class DynamicsWorld;
friend class PhysicsWorld;
friend class GJKAlgorithm;
friend class ConvexMeshShape;
friend class ContactManifoldSet;

View File

@ -27,7 +27,7 @@
#include "collision/CollisionCallback.h"
#include "collision/ContactPair.h"
#include "constraint/ContactPoint.h"
#include "engine/CollisionWorld.h"
#include "engine/PhysicsWorld.h"
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
@ -39,7 +39,7 @@ CollisionCallback::ContactPoint::ContactPoint(const reactphysics3d::ContactPoint
// Contact Pair Constructor
CollisionCallback::ContactPair::ContactPair(const reactphysics3d::ContactPair& contactPair,
List<reactphysics3d::ContactPoint>* contactPoints, CollisionWorld& world)
List<reactphysics3d::ContactPoint>* contactPoints, PhysicsWorld& world)
:mContactPair(contactPair), mContactPoints(contactPoints),
mWorld(world) {
@ -67,7 +67,7 @@ Collider* CollisionCallback::ContactPair::getCollider2() const {
// CollisionCallbackInfo Constructor
CollisionCallback::CallbackData::CallbackData(List<reactphysics3d::ContactPair>* contactPairs, List<ContactManifold>* manifolds,
List<reactphysics3d::ContactPoint>* contactPoints, CollisionWorld& world)
List<reactphysics3d::ContactPoint>* contactPoints, PhysicsWorld &world)
:mContactPairs(contactPairs), mContactManifolds(manifolds), mContactPoints(contactPoints), mWorld(world) {
}

View File

@ -118,13 +118,13 @@ class CollisionCallback {
List<reactphysics3d::ContactPoint>* mContactPoints;
/// Reference to the physics world
CollisionWorld& mWorld;
PhysicsWorld& mWorld;
// -------------------- Methods -------------------- //
/// Constructor
ContactPair(const reactphysics3d::ContactPair& contactPair, List<reactphysics3d::ContactPoint>* contactPoints,
CollisionWorld& world);
PhysicsWorld& world);
public:
@ -182,13 +182,13 @@ class CollisionCallback {
List<reactphysics3d::ContactPoint>* mContactPoints;
/// Reference to the physics world
CollisionWorld& mWorld;
PhysicsWorld& mWorld;
// -------------------- Methods -------------------- //
/// Constructor
CallbackData(List<reactphysics3d::ContactPair>* contactPairs, List<ContactManifold>* manifolds,
List<reactphysics3d::ContactPoint>* contactPoints, CollisionWorld& world);
List<reactphysics3d::ContactPoint>* contactPoints, PhysicsWorld& world);
/// Deleted copy constructor
CallbackData(const CallbackData& callbackData) = delete;

View File

@ -120,7 +120,7 @@ class ContactManifold {
// -------------------- Friendship -------------------- //
friend class DynamicsWorld;
friend class PhysicsWorld;
friend class Island;
friend class CollisionBody;
friend class ContactManifoldSet;

View File

@ -25,13 +25,13 @@
// Libraries
#include "collision/OverlapCallback.h"
#include "engine/CollisionWorld.h"
#include "engine/PhysicsWorld.h"
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
// Contact Pair Constructor
OverlapCallback::OverlapPair::OverlapPair(Pair<Entity, Entity>& overlapPair, CollisionWorld& world)
OverlapCallback::OverlapPair::OverlapPair(Pair<Entity, Entity>& overlapPair, PhysicsWorld& world)
: mOverlapPair(overlapPair), mWorld(world) {
}
@ -47,7 +47,7 @@ CollisionBody* OverlapCallback::OverlapPair::getBody2() const {
}
// CollisionCallbackData Constructor
OverlapCallback::CallbackData::CallbackData(List<Pair<Entity, Entity>>& overlapColliders, CollisionWorld& world)
OverlapCallback::CallbackData::CallbackData(List<Pair<Entity, Entity>>& overlapColliders, PhysicsWorld& world)
:mOverlapBodies(overlapColliders), mWorld(world) {
}

View File

@ -34,7 +34,7 @@ namespace reactphysics3d {
// Declarations
class CollisionBody;
class CollisionWorld;
class PhysicsWorld;
class Collider;
struct Entity;
@ -61,12 +61,12 @@ class OverlapCallback {
Pair<Entity, Entity>& mOverlapPair;
/// Reference to the physics world
CollisionWorld& mWorld;
PhysicsWorld& mWorld;
// -------------------- Methods -------------------- //
/// Constructor
OverlapPair(Pair<Entity, Entity>& overlapPair, CollisionWorld& world);
OverlapPair(Pair<Entity, Entity>& overlapPair, reactphysics3d::PhysicsWorld& world);
public:
@ -105,12 +105,12 @@ class OverlapCallback {
List<Pair<Entity, Entity>>& mOverlapBodies;
/// Reference to the physics world
CollisionWorld& mWorld;
PhysicsWorld& mWorld;
// -------------------- Methods -------------------- //
/// Constructor
CallbackData(List<Pair<Entity, Entity>>& overlapColliders, CollisionWorld& world);
CallbackData(List<Pair<Entity, Entity>>& overlapColliders, PhysicsWorld& world);
/// Deleted copy constructor
CallbackData(const CallbackData& callbackData) = delete;

View File

@ -146,7 +146,7 @@ class CollisionShape {
// -------------------- Friendship -------------------- //
friend class Collider;
friend class CollisionWorld;
friend class PhyscisWorld;
};
// Return the name of the collision shape

View File

@ -26,7 +26,7 @@
// Libraries
#include "configuration.h"
#include "ConvexMeshShape.h"
#include "engine/CollisionWorld.h"
#include "engine/PhysicsWorld.h"
#include "collision/RaycastInfo.h"
using namespace reactphysics3d;

View File

@ -35,9 +35,8 @@
namespace reactphysics3d {
// Declaration
class CollisionWorld;
class GJKAlgorithm;
class CollisionWorld;
class PhysicsWorld;
// Class ConvexMeshShape
/**

View File

@ -156,7 +156,7 @@ class JointComponents : public Components {
friend class BroadPhaseSystem;
friend class ConstraintSolverSystem;
friend class DynamicsWorld;
friend class PhysicsWorld;
};
// Return the entity of the first body of a joint

View File

@ -335,7 +335,7 @@ class RigidBodyComponents : public Components {
// -------------------- Friendship -------------------- //
friend class DynamicsWorld;
friend class PhysicsWorld;
friend class ContactSolverSystem;
friend class SolveBallAndSocketJointSystem;
friend class SolveFixedJointSystem;

View File

@ -112,82 +112,6 @@ constexpr decimal DYNAMIC_TREE_AABB_LIN_GAP_MULTIPLIER = decimal(1.7);
/// Current version of ReactPhysics3D
const std::string RP3D_VERSION = std::string("0.7.1");
/// Structure WorldSettings
/**
* This class is used to describe some settings of a physics world.
*/
struct WorldSettings {
/// Name of the world
std::string worldName = "";
/// Distance threshold for two contact points for a valid persistent contact (in meters)
decimal persistentContactDistanceThreshold = decimal(0.03);
/// Default friction coefficient for a rigid body
decimal defaultFrictionCoefficient = decimal(0.3);
/// Default bounciness factor for a rigid body
decimal defaultBounciness = decimal(0.5);
/// Velocity threshold for contact velocity restitution
decimal restitutionVelocityThreshold = decimal(0.5);
/// 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
uint nbMaxContactManifolds = 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);
/// Return a string with the world settings
std::string to_string() const {
std::stringstream ss;
ss << "worldName=" << worldName << std::endl;
ss << "persistentContactDistanceThreshold=" << persistentContactDistanceThreshold << std::endl;
ss << "defaultFrictionCoefficient=" << defaultFrictionCoefficient << std::endl;
ss << "defaultBounciness=" << defaultBounciness << std::endl;
ss << "restitutionVelocityThreshold=" << restitutionVelocityThreshold << std::endl;
ss << "defaultRollingRestistance=" << defaultRollingRestistance << std::endl;
ss << "isSleepingEnabled=" << isSleepingEnabled << std::endl;
ss << "defaultVelocitySolverNbIterations=" << defaultVelocitySolverNbIterations << std::endl;
ss << "defaultPositionSolverNbIterations=" << defaultPositionSolverNbIterations << std::endl;
ss << "defaultTimeBeforeSleep=" << defaultTimeBeforeSleep << std::endl;
ss << "defaultSleepLinearVelocity=" << defaultSleepLinearVelocity << std::endl;
ss << "defaultSleepAngularVelocity=" << defaultSleepAngularVelocity << std::endl;
ss << "nbMaxContactManifolds=" << nbMaxContactManifolds << std::endl;
ss << "cosAngleSimilarContactManifold=" << cosAngleSimilarContactManifold << std::endl;
return ss.str();
}
};
}
#endif

View File

@ -27,7 +27,7 @@
#include "BallAndSocketJoint.h"
#include "systems/ConstraintSolverSystem.h"
#include "components/RigidBodyComponents.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
using namespace reactphysics3d;
@ -35,7 +35,7 @@ using namespace reactphysics3d;
const decimal BallAndSocketJoint::BETA = decimal(0.2);
// Constructor
BallAndSocketJoint::BallAndSocketJoint(Entity entity, DynamicsWorld& world, const BallAndSocketJointInfo& jointInfo)
BallAndSocketJoint::BallAndSocketJoint(Entity entity, PhysicsWorld& world, const BallAndSocketJointInfo& jointInfo)
: Joint(entity, world) {
// Get the transforms of the two bodies

View File

@ -88,7 +88,7 @@ class BallAndSocketJoint : public Joint {
// -------------------- Methods -------------------- //
/// Constructor
BallAndSocketJoint(Entity entity, DynamicsWorld& world, const BallAndSocketJointInfo& jointInfo);
BallAndSocketJoint(Entity entity, PhysicsWorld& world, const BallAndSocketJointInfo& jointInfo);
/// Destructor
virtual ~BallAndSocketJoint() override = default;

View File

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

View File

@ -75,8 +75,8 @@ class ContactPoint {
/// Pointer to the previous contact point in the double linked-list
ContactPoint* mPrevious;
/// World settings
const WorldSettings& mWorldSettings;
/// Persistent contact distance threshold;
decimal mPersistentContactDistanceThreshold;
// -------------------- Methods -------------------- //
@ -98,10 +98,10 @@ class ContactPoint {
// -------------------- Methods -------------------- //
/// Constructor
ContactPoint(const ContactPointInfo* contactInfo, const WorldSettings& worldSettings);
ContactPoint(const ContactPointInfo* contactInfo, decimal persistentContactDistanceThreshold);
/// Constructor
ContactPoint(const ContactPointInfo& contactInfo, const WorldSettings& worldSettings);
ContactPoint(const ContactPointInfo& contactInfo, decimal persistentContactDistanceThreshold);
/// Destructor
~ContactPoint() = default;
@ -174,8 +174,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() <= (mWorldSettings.persistentContactDistanceThreshold *
mWorldSettings.persistentContactDistanceThreshold);
return (localContactPointBody1->localPoint1 - mLocalPointOnShape1).lengthSquare() <= (mPersistentContactDistanceThreshold *
mPersistentContactDistanceThreshold);
}
// Set the cached penetration impulse

View File

@ -27,12 +27,12 @@
#include "FixedJoint.h"
#include "systems/ConstraintSolverSystem.h"
#include "components/RigidBodyComponents.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
using namespace reactphysics3d;
// Constructor
FixedJoint::FixedJoint(Entity entity, DynamicsWorld &world, const FixedJointInfo& jointInfo)
FixedJoint::FixedJoint(Entity entity, PhysicsWorld &world, const FixedJointInfo& jointInfo)
: Joint(entity, world) {
// Compute the local-space anchor point for each body

View File

@ -78,7 +78,7 @@ class FixedJoint : public Joint {
// -------------------- Methods -------------------- //
/// Constructor
FixedJoint(Entity entity, DynamicsWorld& world, const FixedJointInfo& jointInfo);
FixedJoint(Entity entity, PhysicsWorld& world, const FixedJointInfo& jointInfo);
/// Destructor
virtual ~FixedJoint() override = default;

View File

@ -27,12 +27,12 @@
#include "HingeJoint.h"
#include "systems/ConstraintSolverSystem.h"
#include "components/RigidBodyComponents.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
using namespace reactphysics3d;
// Constructor
HingeJoint::HingeJoint(Entity entity, DynamicsWorld &world, const HingeJointInfo& jointInfo) : Joint(entity, world) {
HingeJoint::HingeJoint(Entity entity, PhysicsWorld &world, const HingeJointInfo& jointInfo) : Joint(entity, world) {
const decimal lowerLimit = mWorld.mHingeJointsComponents.getLowerLimit(mEntity);
const decimal upperLimit = mWorld.mHingeJointsComponents.getUpperLimit(mEntity);

View File

@ -160,7 +160,7 @@ class HingeJoint : public Joint {
// -------------------- Methods -------------------- //
/// Constructor
HingeJoint(Entity entity, DynamicsWorld& world, const HingeJointInfo& jointInfo);
HingeJoint(Entity entity, PhysicsWorld& world, const HingeJointInfo& jointInfo);
/// Destructor
virtual ~HingeJoint() override = default;

View File

@ -25,12 +25,12 @@
// Libraries
#include "Joint.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
using namespace reactphysics3d;
// Constructor
Joint::Joint(Entity entity, DynamicsWorld& world) :mEntity(entity), mWorld(world) {
Joint::Joint(Entity entity, PhysicsWorld& world) :mEntity(entity), mWorld(world) {
}

View File

@ -40,6 +40,7 @@ enum class JointType {BALLSOCKETJOINT, SLIDERJOINT, HINGEJOINT, FIXEDJOINT};
// Class declarations
struct ConstraintSolverData;
class Joint;
class RigidBody;
// Structure JointInfo
/**
@ -71,7 +72,9 @@ struct JointInfo {
JointInfo(JointType constraintType)
: body1(nullptr), body2(nullptr), type(constraintType),
positionCorrectionTechnique(JointsPositionCorrectionTechnique::NON_LINEAR_GAUSS_SEIDEL),
isCollisionEnabled(true) {}
isCollisionEnabled(true) {
}
/// Constructor
JointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, JointType constraintType)
@ -99,7 +102,7 @@ class Joint {
Entity mEntity;
/// Reference to the physics world
DynamicsWorld& mWorld;
PhysicsWorld& mWorld;
// -------------------- Methods -------------------- //
@ -114,7 +117,7 @@ class Joint {
// -------------------- Methods -------------------- //
/// Constructor
Joint(Entity entity, DynamicsWorld& world);
Joint(Entity entity, PhysicsWorld& world);
/// Destructor
virtual ~Joint() = default;
@ -145,7 +148,7 @@ class Joint {
// -------------------- Friendship -------------------- //
friend class DynamicsWorld;
friend class PhysicsWorld;
friend class Island;
friend class ConstraintSolverSystem;
};

View File

@ -27,7 +27,7 @@
#include "SliderJoint.h"
#include "systems/ConstraintSolverSystem.h"
#include "components/RigidBodyComponents.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
using namespace reactphysics3d;
@ -35,7 +35,7 @@ using namespace reactphysics3d;
const decimal SliderJoint::BETA = decimal(0.2);
// Constructor
SliderJoint::SliderJoint(Entity entity, DynamicsWorld &world, const SliderJointInfo& jointInfo)
SliderJoint::SliderJoint(Entity entity, PhysicsWorld &world, const SliderJointInfo& jointInfo)
: Joint(entity, world) {
assert(mWorld.mSliderJointsComponents.getUpperLimit(mEntity) >= decimal(0.0));

View File

@ -163,7 +163,7 @@ class SliderJoint : public Joint {
// -------------------- Methods -------------------- //
/// Constructor
SliderJoint(Entity entity, DynamicsWorld& world, const SliderJointInfo& jointInfo);
SliderJoint(Entity entity, PhysicsWorld& world, const SliderJointInfo& jointInfo);
/// Destructor
virtual ~SliderJoint() override = default;

View File

@ -119,8 +119,11 @@ class Stack {
clear();
// Release the memory allocated on the heap
mAllocator.release(mArray, mCapacity * sizeof(T));
if (mCapacity > 0) {
// Release the memory allocated on the heap
mAllocator.release(mArray, mCapacity * sizeof(T));
}
}
/// Remove all the items from the stack

View File

@ -1,303 +0,0 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2019 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
// Libraries
#include "CollisionWorld.h"
#include "utils/Profiler.h"
#include "utils/Logger.h"
// Namespaces
using namespace reactphysics3d;
using namespace std;
// Initialization of static fields
uint CollisionWorld::mNbWorlds = 0;
// Constructor
CollisionWorld::CollisionWorld(MemoryManager& memoryManager, const WorldSettings& worldSettings, Logger* logger, Profiler* profiler)
: mMemoryManager(memoryManager), mConfig(worldSettings), mEntityManager(mMemoryManager.getHeapAllocator()),
mCollisionBodyComponents(mMemoryManager.getHeapAllocator()), mRigidBodyComponents(mMemoryManager.getHeapAllocator()),
mTransformComponents(mMemoryManager.getHeapAllocator()), mCollidersComponents(mMemoryManager.getHeapAllocator()),
mJointsComponents(mMemoryManager.getHeapAllocator()), mBallAndSocketJointsComponents(mMemoryManager.getHeapAllocator()),
mFixedJointsComponents(mMemoryManager.getHeapAllocator()), mHingeJointsComponents(mMemoryManager.getHeapAllocator()),
mSliderJointsComponents(mMemoryManager.getHeapAllocator()),
mCollisionDetection(this, mCollidersComponents, mTransformComponents, mCollisionBodyComponents, mRigidBodyComponents, mMemoryManager),
mBodies(mMemoryManager.getHeapAllocator()), mEventListener(nullptr),
mName(worldSettings.worldName), mIsProfilerCreatedByUser(profiler != nullptr),
mIsLoggerCreatedByUser(logger != nullptr) {
// Automatically generate a name for the world
if (mName == "") {
std::stringstream ss;
ss << "world";
if (mNbWorlds > 0) {
ss << mNbWorlds;
}
mName = ss.str();
}
#ifdef IS_PROFILING_ACTIVE
mProfiler = profiler;
// If the user has not provided its own profiler, we create one
if (mProfiler == nullptr) {
mProfiler = new Profiler();
// Add a destination file for the profiling data
mProfiler->addFileDestination("rp3d_profiling_" + mName + ".txt", Profiler::Format::Text);
}
// Set the profiler
mCollisionDetection.setProfiler(mProfiler);
#endif
#ifdef IS_LOGGING_ACTIVE
mLogger = logger;
// If the user has not provided its own logger, we create one
if (mLogger == nullptr) {
mLogger = new Logger();
// Add a log destination file
uint logLevel = static_cast<uint>(Logger::Level::Information) | static_cast<uint>(Logger::Level::Warning) |
static_cast<uint>(Logger::Level::Error);
mLogger->addFileDestination("rp3d_log_" + mName + ".html", logLevel, Logger::Format::HTML);
}
#endif
mNbWorlds++;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Collision World: Collision world " + mName + " has been created");
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Collision World: Initial world settings: " + worldSettings.to_string());
}
// Destructor
CollisionWorld::~CollisionWorld() {
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Collision World: Collision world " + mName + " has been destroyed");
// Destroy all the collision bodies that have not been removed
for (int i=mBodies.size() - 1 ; i >= 0; i--) {
destroyCollisionBody(mBodies[i]);
}
#ifdef IS_PROFILING_ACTIVE
/// Delete the profiler
if (!mIsProfilerCreatedByUser) {
delete mProfiler;
}
#endif
#ifdef IS_LOGGING_ACTIVE
/// Delete the logger
if (!mIsLoggerCreatedByUser) {
delete mLogger;
}
#endif
assert(mBodies.size() == 0);
assert(mCollisionBodyComponents.getNbComponents() == 0);
assert(mTransformComponents.getNbComponents() == 0);
assert(mCollidersComponents.getNbComponents() == 0);
}
// Create a collision body and add it to the world
/**
* @param transform Transformation mapping the local-space of the body to world-space
* @return A pointer to the body that has been created in the world
*/
CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) {
// Create a new entity for the body
Entity entity = mEntityManager.createEntity();
mTransformComponents.addComponent(entity, false, TransformComponents::TransformComponent(transform));
// Create the collision body
CollisionBody* collisionBody = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool,
sizeof(CollisionBody)))
CollisionBody(*this, entity);
assert(collisionBody != nullptr);
// Add the components
CollisionBodyComponents::CollisionBodyComponent bodyComponent(collisionBody);
mCollisionBodyComponents.addComponent(entity, false, bodyComponent);
// Add the collision body to the world
mBodies.add(collisionBody);
#ifdef IS_PROFILING_ACTIVE
collisionBody->setProfiler(mProfiler);
#endif
#ifdef IS_LOGGING_ACTIVE
collisionBody->setLogger(mLogger);
#endif
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body,
"Body " + std::to_string(entity.id) + ": New collision body created");
// Return the pointer to the rigid body
return collisionBody;
}
// Destroy a collision body
/**
* @param collisionBody Pointer to the body to destroy
*/
void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) {
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body,
"Body " + std::to_string(collisionBody->getEntity().id) + ": collision body destroyed");
// Remove all the collision shapes of the body
collisionBody->removeAllCollisionShapes();
mCollisionBodyComponents.removeComponent(collisionBody->getEntity());
mTransformComponents.removeComponent(collisionBody->getEntity());
mEntityManager.destroyEntity(collisionBody->getEntity());
// Call the destructor of the collision body
collisionBody->~CollisionBody();
// Remove the collision body from the list of bodies
mBodies.remove(collisionBody);
// Free the object from the memory allocator
mMemoryManager.release(MemoryManager::AllocationType::Pool, collisionBody, sizeof(CollisionBody));
}
// Notify the world if a body is disabled (sleeping) or not
void CollisionWorld::setBodyDisabled(Entity bodyEntity, bool isDisabled) {
if (isDisabled == mCollisionBodyComponents.getIsEntityDisabled(bodyEntity)) return;
// Notify all the components
mCollisionBodyComponents.setIsEntityDisabled(bodyEntity, isDisabled);
mTransformComponents.setIsEntityDisabled(bodyEntity, isDisabled);
if (mRigidBodyComponents.hasComponent(bodyEntity)) {
mRigidBodyComponents.setIsEntityDisabled(bodyEntity, isDisabled);
}
// For each collider of the body
const List<Entity>& collidersEntities = mCollisionBodyComponents.getColliders(bodyEntity);
for (uint i=0; i < collidersEntities.size(); i++) {
mCollidersComponents.setIsEntityDisabled(collidersEntities[i], isDisabled);
}
// Disable the joints of the body if necessary
if (mRigidBodyComponents.hasComponent(bodyEntity)) {
// For each joint of the body
const List<Entity>& joints = mRigidBodyComponents.getJoints(bodyEntity);
for(uint32 i=0; i < joints.size(); i++) {
const Entity body1Entity = mJointsComponents.getBody1Entity(joints[i]);
const Entity body2Entity = mJointsComponents.getBody2Entity(joints[i]);
// If both bodies of the joint are disabled
if (mRigidBodyComponents.getIsEntityDisabled(body1Entity) &&
mRigidBodyComponents.getIsEntityDisabled(body2Entity)) {
// We disable the joint
setJointDisabled(joints[i], true);
}
else {
// Enable the joint
setJointDisabled(joints[i], false);
}
}
}
}
// Notify the world whether a joint is disabled or not
void CollisionWorld::setJointDisabled(Entity jointEntity, bool isDisabled) {
if (isDisabled == mJointsComponents.getIsEntityDisabled(jointEntity)) return;
mJointsComponents.setIsEntityDisabled(jointEntity, isDisabled);
if (mBallAndSocketJointsComponents.hasComponent(jointEntity)) {
mBallAndSocketJointsComponents.setIsEntityDisabled(jointEntity, isDisabled);
}
if (mFixedJointsComponents.hasComponent(jointEntity)) {
mFixedJointsComponents.setIsEntityDisabled(jointEntity, isDisabled);
}
if (mHingeJointsComponents.hasComponent(jointEntity)) {
mHingeJointsComponents.setIsEntityDisabled(jointEntity, isDisabled);
}
if (mSliderJointsComponents.hasComponent(jointEntity)) {
mSliderJointsComponents.setIsEntityDisabled(jointEntity, isDisabled);
}
}
// Return true if two bodies overlap
/// Use this method if you are not interested in contacts but if you simply want to know
/// if the two bodies overlap. If you want to get the contacts, you need to use the
/// testCollision() method instead.
/**
* @param body1 Pointer to the first body
* @param body2 Pointer to a second body
* @return True if the two bodies overlap
*/
bool CollisionWorld::testOverlap(CollisionBody* body1, CollisionBody* body2) {
return mCollisionDetection.testOverlap(body1, body2);
}
// Return the current world-space AABB of given collider
/**
* @param collider Pointer to a collider
* @return The AAABB of the collider in world-space
*/
AABB CollisionWorld::getWorldAABB(const Collider* collider) const {
if (collider->getBroadPhaseId() == -1) {
return AABB();
}
return mCollisionDetection.getWorldAABB(collider);
}

View File

@ -1,356 +0,0 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2019 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_COLLISION_WORLD_H
#define REACTPHYSICS3D_COLLISION_WORLD_H
// Libraries
#include "mathematics/mathematics.h"
#include "containers/List.h"
#include "systems/CollisionDetectionSystem.h"
#include "constraint/Joint.h"
#include "memory/MemoryManager.h"
#include "engine/EntityManager.h"
#include "components/CollisionBodyComponents.h"
#include "components/RigidBodyComponents.h"
#include "components/TransformComponents.h"
#include "components/ColliderComponents.h"
#include "components/JointComponents.h"
#include "components/BallAndSocketJointComponents.h"
#include "components/FixedJointComponents.h"
#include "components/HingeJointComponents.h"
#include "components/SliderJointComponents.h"
#include "collision/CollisionCallback.h"
#include "collision/OverlapCallback.h"
/// Namespace reactphysics3d
namespace reactphysics3d {
// Declarations
class Profiler;
class Logger;
class EventListener;
class Joint;
class ContactPoint;
class OverlappingPair;
class CollisionBody;
struct RaycastInfo;
class CollisionCallback;
class OverlapCallback;
// 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 -------------------- //
/// Memory manager
MemoryManager& mMemoryManager;
/// Configuration of the physics world
WorldSettings mConfig;
/// Entity Manager for the ECS
EntityManager mEntityManager;
/// Collision Body Components
CollisionBodyComponents mCollisionBodyComponents;
/// Rigid Body Components
RigidBodyComponents mRigidBodyComponents;
/// Transform Components
TransformComponents mTransformComponents;
/// Collider Components
ColliderComponents mCollidersComponents;
/// Joint Components
JointComponents mJointsComponents;
/// Ball And Socket joints Components
BallAndSocketJointComponents mBallAndSocketJointsComponents;
/// Fixed joints Components
FixedJointComponents mFixedJointsComponents;
/// Hinge joints Components
HingeJointComponents mHingeJointsComponents;
/// Slider joints Components
SliderJointComponents mSliderJointsComponents;
/// Reference to the collision detection
CollisionDetectionSystem mCollisionDetection;
/// All the bodies (rigid and soft) of the world
List<CollisionBody*> mBodies;
/// Pointer to an event listener object
EventListener* mEventListener;
/// Name of the collision world
std::string mName;
#ifdef IS_PROFILING_ACTIVE
/// Real-time hierarchical profiler
Profiler* mProfiler;
#endif
#ifdef IS_LOGGING_ACTIVE
/// Logger
Logger* mLogger;
#endif
/// True if the profiler has been created by the user
bool mIsProfilerCreatedByUser;
/// True if the logger has been created by the user
bool mIsLoggerCreatedByUser;
/// Total number of worlds
static uint mNbWorlds;
// -------------------- Methods -------------------- //
/// Constructor
CollisionWorld(MemoryManager& memoryManager, const WorldSettings& worldSettings = WorldSettings(), Logger* logger = nullptr,
Profiler* profiler = nullptr);
/// Notify the world if a body is disabled (slepping or inactive) or not
void setBodyDisabled(Entity entity, bool isDisabled);
/// Notify the world whether a joint is disabled or not
void setJointDisabled(Entity jointEntity, bool isDisabled);
/// Destructor
virtual ~CollisionWorld();
public :
// -------------------- Methods -------------------- //
/// Deleted copy-constructor
CollisionWorld(const CollisionWorld& world) = delete;
/// Deleted assignment operator
CollisionWorld& operator=(const CollisionWorld& world) = delete;
/// Create a collision body
CollisionBody* createCollisionBody(const Transform& transform);
/// Destroy a collision body
void destroyCollisionBody(CollisionBody* collisionBody);
/// Get the collision dispatch configuration
CollisionDispatch& getCollisionDispatch();
/// Ray cast method
void raycast(const Ray& ray, RaycastCallback* raycastCallback, unsigned short raycastWithCategoryMaskBits = 0xFFFF) const;
/// Return true if two bodies overlap (collide)
bool testOverlap(CollisionBody* body1, CollisionBody* body2);
/// Report all the bodies that overlap (collide) with the body in parameter
void testOverlap(CollisionBody* body, OverlapCallback& overlapCallback);
/// Report all the bodies that overlap (collide) in the world
void testOverlap(OverlapCallback& overlapCallback);
/// Test collision and report contacts between two bodies.
void testCollision(CollisionBody* body1, CollisionBody* body2, CollisionCallback& callback);
/// Test collision and report all the contacts involving the body in parameter
void testCollision(CollisionBody* body, CollisionCallback& callback);
/// Test collision and report contacts between each colliding bodies in the world
void testCollision(CollisionCallback& callback);
/// Return a reference to the memory manager of the world
MemoryManager& getMemoryManager();
#ifdef IS_PROFILING_ACTIVE
/// Return a reference to the profiler
Profiler* getProfiler();
#endif
#ifdef IS_LOGGING_ACTIVE
/// Return a reference to the logger
Logger* getLogger();
#endif
/// Return the current world-space AABB of given collider
AABB getWorldAABB(const Collider* collider) const;
/// Return the name of the world
const std::string& getName() const;
// -------------------- Friendship -------------------- //
friend class PhysicsCommon;
friend class CollisionDetectionSystem;
friend class CollisionBody;
friend class RigidBody;
friend class Collider;
friend class ConvexMeshShape;
friend class CollisionCallback::ContactPair;
friend class OverlapCallback::OverlapPair;
};
// Set the collision dispatch configuration
/// This can be used to replace default collision detection algorithms by your
/// custom algorithm for instance.
/**
* @param CollisionDispatch Pointer to a collision dispatch object describing
* which collision detection algorithm to use for two given collision shapes
*/
inline CollisionDispatch& CollisionWorld::getCollisionDispatch() {
return mCollisionDetection.getCollisionDispatch();
}
// Ray cast method
/**
* @param ray Ray to use for raycasting
* @param raycastCallback Pointer to the class with the callback method
* @param raycastWithCategoryMaskBits Bits mask corresponding to the category of
* bodies to be raycasted
*/
inline void CollisionWorld::raycast(const Ray& ray,
RaycastCallback* raycastCallback,
unsigned short raycastWithCategoryMaskBits) const {
mCollisionDetection.raycast(raycastCallback, ray, raycastWithCategoryMaskBits);
}
// Test collision and report contacts between two bodies.
/// Use this method if you only want to get all the contacts between two bodies.
/// All the contacts will be reported using the callback object in paramater.
/// If you are not interested in the contacts but you only want to know if the bodies collide,
/// you can use the testOverlap() method instead.
/**
* @param body1 Pointer to the first body to test
* @param body2 Pointer to the second body to test
* @param callback Pointer to the object with the callback method
*/
inline void CollisionWorld::testCollision(CollisionBody* body1, CollisionBody* body2, CollisionCallback& callback) {
mCollisionDetection.testCollision(body1, body2, callback);
}
// Test collision and report all the contacts involving the body in parameter
/// Use this method if you only want to get all the contacts involving a given body.
/// All the contacts will be reported using the callback object in paramater.
/// If you are not interested in the contacts but you only want to know if the bodies collide,
/// you can use the testOverlap() method instead.
/**
* @param body Pointer to the body against which we need to test collision
* @param callback Pointer to the object with the callback method to report contacts
*/
inline void CollisionWorld::testCollision(CollisionBody* body, CollisionCallback& callback) {
mCollisionDetection.testCollision(body, callback);
}
// Test collision and report contacts between each colliding bodies in the world
/// Use this method if you want to get all the contacts between colliding bodies in the world.
/// All the contacts will be reported using the callback object in paramater.
/// If you are not interested in the contacts but you only want to know if the bodies collide,
/// you can use the testOverlap() method instead.
/**
* @param callback Pointer to the object with the callback method to report contacts
*/
inline void CollisionWorld::testCollision(CollisionCallback& callback) {
mCollisionDetection.testCollision(callback);
}
// Report all the bodies that overlap (collide) with the body in parameter
/// Use this method if you are not interested in contacts but if you simply want to know
/// which bodies overlap with the body in parameter. If you want to get the contacts, you need to use the
/// testCollision() method instead.
/**
* @param body Pointer to the collision body to test overlap with
* @param overlapCallback Pointer to the callback class to report overlap
*/
inline void CollisionWorld::testOverlap(CollisionBody* body, OverlapCallback& overlapCallback) {
mCollisionDetection.testOverlap(body, overlapCallback);
}
// Report all the bodies that overlap (collide) in the world
/// Use this method if you are not interested in contacts but if you simply want to know
/// which bodies overlap. If you want to get the contacts, you need to use the
/// testCollision() method instead.
inline void CollisionWorld::testOverlap(OverlapCallback& overlapCallback) {
mCollisionDetection.testOverlap(overlapCallback);
}
// Return a reference to the memory manager of the world
inline MemoryManager& CollisionWorld::getMemoryManager() {
return mMemoryManager;
}
// Return the name of the world
/**
* @return Name of the world
*/
inline const std::string& CollisionWorld::getName() const {
return mName;
}
#ifdef IS_PROFILING_ACTIVE
// Return a pointer to the profiler
/**
* @return A pointer to the profiler
*/
inline Profiler* CollisionWorld::getProfiler() {
return mProfiler;
}
#endif
#ifdef IS_LOGGING_ACTIVE
// Return a pointer to the logger
/**
* @return A pointer to the logger
*/
inline Logger* CollisionWorld::getLogger() {
return mLogger;
}
#endif
}
#endif

View File

@ -1,415 +0,0 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2019 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_DYNAMICS_WORLD_H
#define REACTPHYSICS3D_DYNAMICS_WORLD_H
// Libraries
#include "CollisionWorld.h"
#include "systems/ConstraintSolverSystem.h"
#include "configuration.h"
#include "utils/Logger.h"
#include "systems/ContactSolverSystem.h"
#include "systems/DynamicsSystem.h"
#include "engine/Islands.h"
/// Namespace ReactPhysics3D
namespace reactphysics3d {
// Declarations
class CollisionDetectionSystem;
class Island;
class RigidBody;
// 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 -------------------- //
/// All the islands of bodies of the current frame
Islands mIslands;
/// Contact solver system
ContactSolverSystem mContactSolverSystem;
/// Constraint solver system
ConstraintSolverSystem mConstraintSolverSystem;
/// Dynamics system
DynamicsSystem mDynamicsSystem;
/// Number of iterations for the velocity solver of the Sequential Impulses technique
uint mNbVelocitySolverIterations;
/// Number of iterations for the position solver of the Sequential Impulses technique
uint mNbPositionSolverIterations;
/// True if the spleeping technique for inactive bodies is enabled
bool mIsSleepingEnabled;
/// All the rigid bodies of the physics world
List<RigidBody*> mRigidBodies;
/// Gravity vector of the world
Vector3 mGravity;
/// True if the gravity force is on
bool mIsGravityEnabled;
/// Sleep linear velocity threshold
decimal mSleepLinearVelocity;
/// Sleep angular velocity threshold
decimal mSleepAngularVelocity;
/// Time (in seconds) before a body is put to sleep if its velocity
/// becomes smaller than the sleep velocity.
decimal mTimeBeforeSleep;
/// Current joint id
uint mCurrentJointId;
// -------------------- Methods -------------------- //
/// Constructor
DynamicsWorld(const Vector3& mGravity, MemoryManager& memoryManager, const WorldSettings& worldSettings = WorldSettings(),
Logger* logger = nullptr, Profiler* profiler = nullptr);
/// Solve the contacts and constraints
void solveContactsAndConstraints(decimal timeStep);
/// Solve the position error correction of the constraints
void solvePositionCorrection();
/// Compute the islands of awake bodies.
void computeIslands();
/// Compute the islands using potential contacts and joints and create the actual contacts.
void createIslands();
/// Put bodies to sleep if needed.
void updateSleepingBodies(decimal timeStep);
/// Add the joint to the list of joints of the two bodies involved in the joint
void addJointToBodies(Entity body1, Entity body2, Entity joint);
/// Destructor
virtual ~DynamicsWorld() override;
public :
// -------------------- Methods -------------------- //
/// Deleted copy-constructor
DynamicsWorld(const DynamicsWorld& world) = delete;
/// Deleted assignment operator
DynamicsWorld& operator=(const DynamicsWorld& world) = delete;
/// Update the physics simulation
void update(decimal timeStep);
/// Get the number of iterations for the velocity constraint solver
uint getNbIterationsVelocitySolver() const;
/// Set the number of iterations for the velocity constraint solver
void setNbIterationsVelocitySolver(uint nbIterations);
/// Get the number of iterations for the position constraint solver
uint getNbIterationsPositionSolver() const;
/// Set the number of iterations for the position constraint solver
void setNbIterationsPositionSolver(uint nbIterations);
/// Set the position correction technique used for contacts
void setContactsPositionCorrectionTechnique(ContactsPositionCorrectionTechnique technique);
/// Set the position correction technique used for joints
void setJointsPositionCorrectionTechnique(JointsPositionCorrectionTechnique technique);
/// Create a rigid body into the physics world.
RigidBody* createRigidBody(const Transform& transform);
/// Disable the joints for pair of sleeping bodies
void disableJointsOfSleepingBodies();
/// Destroy a rigid body and all the joints which it belongs
void destroyRigidBody(RigidBody* rigidBody);
/// Create a joint between two bodies in the world and return a pointer to the new joint
Joint* createJoint(const JointInfo& jointInfo);
/// Destroy a joint
void destroyJoint(Joint* joint);
/// Return the gravity vector of the world
Vector3 getGravity() const;
/// Set the gravity vector of the world
void setGravity(Vector3& gravity);
/// Return if the gravity is on
bool isGravityEnabled() const;
/// Enable/Disable the gravity
void setIsGratityEnabled(bool isGravityEnabled);
/// Return true if the sleeping technique is enabled
bool isSleepingEnabled() const;
/// Enable/Disable the sleeping technique
void enableSleeping(bool isSleepingEnabled);
/// Return the current sleep linear velocity
decimal getSleepLinearVelocity() const;
/// Set the sleep linear velocity.
void setSleepLinearVelocity(decimal sleepLinearVelocity);
/// Return the current sleep angular velocity
decimal getSleepAngularVelocity() const;
/// Set the sleep angular velocity.
void setSleepAngularVelocity(decimal sleepAngularVelocity);
/// Return the time a body is required to stay still before sleeping
decimal getTimeBeforeSleep() const;
/// Set the time a body is required to stay still before sleeping
void setTimeBeforeSleep(decimal timeBeforeSleep);
/// Set an event listener object to receive events callbacks.
void setEventListener(EventListener* eventListener);
// -------------------- Friendship -------------------- //
friend class PhysicsCommon;
friend class RigidBody;
friend class Joint;
friend class BallAndSocketJoint;
friend class FixedJoint;
friend class HingeJoint;
friend class SliderJoint;
};
// Get the number of iterations for the velocity constraint solver
/**
* @return The number of iterations of the velocity constraint solver
*/
inline uint DynamicsWorld::getNbIterationsVelocitySolver() const {
return mNbVelocitySolverIterations;
}
// Set the number of iterations for the velocity constraint solver
/**
* @param nbIterations Number of iterations for the velocity solver
*/
inline void DynamicsWorld::setNbIterationsVelocitySolver(uint nbIterations) {
mNbVelocitySolverIterations = nbIterations;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Dynamics World: Set nb iterations velocity solver to " + std::to_string(nbIterations));
}
// Get the number of iterations for the position constraint solver
/**
* @return The number of iterations of the position constraint solver
*/
inline uint DynamicsWorld::getNbIterationsPositionSolver() const {
return mNbPositionSolverIterations;
}
// Set the number of iterations for the position constraint solver
/**
* @param nbIterations Number of iterations for the position solver
*/
inline void DynamicsWorld::setNbIterationsPositionSolver(uint nbIterations) {
mNbPositionSolverIterations = nbIterations;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Dynamics World: Set nb iterations position solver to " + std::to_string(nbIterations));
}
// Set the position correction technique used for contacts
/**
* @param technique Technique used for the position correction (Baumgarte or Split Impulses)
*/
inline void DynamicsWorld::setContactsPositionCorrectionTechnique(
ContactsPositionCorrectionTechnique technique) {
if (technique == ContactsPositionCorrectionTechnique::BAUMGARTE_CONTACTS) {
mContactSolverSystem.setIsSplitImpulseActive(false);
}
else {
mContactSolverSystem.setIsSplitImpulseActive(true);
}
}
// Set the position correction technique used for joints
/**
* @param technique Technique used for the joins position correction (Baumgarte or Non Linear Gauss Seidel)
*/
inline void DynamicsWorld::setJointsPositionCorrectionTechnique(
JointsPositionCorrectionTechnique technique) {
if (technique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) {
mConstraintSolverSystem.setIsNonLinearGaussSeidelPositionCorrectionActive(false);
}
else {
mConstraintSolverSystem.setIsNonLinearGaussSeidelPositionCorrectionActive(true);
}
}
// Return the gravity vector of the world
/**
* @return The current gravity vector (in meter per seconds squared)
*/
inline Vector3 DynamicsWorld::getGravity() const {
return mGravity;
}
// Set the gravity vector of the world
/**
* @param gravity The gravity vector (in meter per seconds squared)
*/
inline void DynamicsWorld::setGravity(Vector3& gravity) {
mGravity = gravity;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Dynamics World: Set gravity vector to " + gravity.to_string());
}
// Return if the gravity is enaled
/**
* @return True if the gravity is enabled in the world
*/
inline bool DynamicsWorld::isGravityEnabled() const {
return mIsGravityEnabled;
}
// Enable/Disable the gravity
/**
* @param isGravityEnabled True if you want to enable the gravity in the world
* and false otherwise
*/
inline void DynamicsWorld::setIsGratityEnabled(bool isGravityEnabled) {
mIsGravityEnabled = isGravityEnabled;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Dynamics World: isGravityEnabled= " + (isGravityEnabled ? std::string("true") : std::string("false")));
}
// Return true if the sleeping technique is enabled
/**
* @return True if the sleeping technique is enabled and false otherwise
*/
inline bool DynamicsWorld::isSleepingEnabled() const {
return mIsSleepingEnabled;
}
// Return the current sleep linear velocity
/**
* @return The sleep linear velocity (in meters per second)
*/
inline decimal DynamicsWorld::getSleepLinearVelocity() const {
return mSleepLinearVelocity;
}
// Set the sleep linear velocity.
/// When the velocity of a body becomes smaller than the sleep linear/angular
/// velocity for a given amount of time, the body starts sleeping and does not need
/// to be simulated anymore.
/**
* @param sleepLinearVelocity The sleep linear velocity (in meters per second)
*/
inline void DynamicsWorld::setSleepLinearVelocity(decimal sleepLinearVelocity) {
assert(sleepLinearVelocity >= decimal(0.0));
mSleepLinearVelocity = sleepLinearVelocity;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Dynamics World: sleepLinearVelocity= " + std::to_string(sleepLinearVelocity));
}
// Return the current sleep angular velocity
/**
* @return The sleep angular velocity (in radian per second)
*/
inline decimal DynamicsWorld::getSleepAngularVelocity() const {
return mSleepAngularVelocity;
}
// Set the sleep angular velocity.
/// When the velocity of a body becomes smaller than the sleep linear/angular
/// velocity for a given amount of time, the body starts sleeping and does not need
/// to be simulated anymore.
/**
* @param sleepAngularVelocity The sleep angular velocity (in radian per second)
*/
inline void DynamicsWorld::setSleepAngularVelocity(decimal sleepAngularVelocity) {
assert(sleepAngularVelocity >= decimal(0.0));
mSleepAngularVelocity = sleepAngularVelocity;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Dynamics World: sleepAngularVelocity= " + std::to_string(sleepAngularVelocity));
}
// Return the time a body is required to stay still before sleeping
/**
* @return Time a body is required to stay still before sleeping (in seconds)
*/
inline decimal DynamicsWorld::getTimeBeforeSleep() const {
return mTimeBeforeSleep;
}
// Set the time a body is required to stay still before sleeping
/**
* @param timeBeforeSleep Time a body is required to stay still before sleeping (in seconds)
*/
inline void DynamicsWorld::setTimeBeforeSleep(decimal timeBeforeSleep) {
assert(timeBeforeSleep >= decimal(0.0));
mTimeBeforeSleep = timeBeforeSleep;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Dynamics World: timeBeforeSleep= " + std::to_string(timeBeforeSleep));
}
// Set an event listener object to receive events callbacks.
/// If you use "nullptr" as an argument, the events callbacks will be disabled.
/**
* @param eventListener Pointer to the event listener object that will receive
* event callbacks during the simulation
*/
inline void DynamicsWorld::setEventListener(EventListener* eventListener) {
mEventListener = eventListener;
}
}
#endif

View File

@ -36,7 +36,7 @@ namespace reactphysics3d {
* This class can be used to receive event callbacks from the physics engine.
* In order to receive callbacks, you need to create a new class that inherits from
* this one and you must override the methods you need. Then, you need to register your
* new event listener class to the physics world using the DynamicsWorld::setEventListener()
* new event listener class to the physics world using the PhysicsWorld::setEventListener()
* method.
*/
class EventListener : public CollisionCallback {

View File

@ -101,7 +101,7 @@ class Island {
// -------------------- Friendship -------------------- //
friend class DynamicsWorld;
friend class PhysicsWorld;
};
// Add a body into the island

View File

@ -29,16 +29,14 @@
using namespace reactphysics3d;
// Constructor
Material::Material(const WorldSettings& worldSettings)
: mFrictionCoefficient(worldSettings.defaultFrictionCoefficient),
mRollingResistance(worldSettings.defaultRollingRestistance),
mBounciness(worldSettings.defaultBounciness) {
Material::Material(decimal frictionCoefficient, decimal rollingResistance, decimal bounciness)
: mFrictionCoefficient(frictionCoefficient), mRollingResistance(rollingResistance), mBounciness(bounciness) {
}
// Copy-constructor
Material::Material(const Material& material)
: mFrictionCoefficient(material.mFrictionCoefficient),
mRollingResistance(material.mRollingResistance), mBounciness(material.mBounciness) {
: mFrictionCoefficient(material.mFrictionCoefficient), mRollingResistance(material.mRollingResistance),
mBounciness(material.mBounciness) {
}

View File

@ -53,12 +53,10 @@ class Material {
/// Bounciness during collisions (between 0 and 1) where 1 is for a very bouncy body
decimal mBounciness;
public :
// -------------------- Methods -------------------- //
/// Constructor
Material(const WorldSettings& worldSettings);
Material(decimal frictionCoefficient, decimal rollingResistance, decimal bounciness);
/// Copy-constructor
Material(const Material& material);
@ -66,6 +64,10 @@ class Material {
/// Destructor
~Material() = default;
public :
// -------------------- Methods -------------------- //
/// Return the bounciness
decimal getBounciness() const;
@ -89,6 +91,10 @@ class Material {
/// Overloaded assignment operator
Material& operator=(const Material& material);
// ---------- Friendship ---------- //
friend class RigidBody;
};
// Return the bounciness

View File

@ -291,7 +291,7 @@ class OverlappingPairs {
// -------------------- Friendship -------------------- //
friend class DynamicsWorld;
friend class PhysicsWorld;
friend class CollisionDetectionSystem;
};

View File

@ -30,8 +30,8 @@ using namespace reactphysics3d;
/// Constructor
PhysicsCommon::PhysicsCommon(MemoryAllocator* baseMemoryAllocator)
: mMemoryManager(baseMemoryAllocator), mCollisionWorlds(mMemoryManager.getHeapAllocator()),
mDynamicsWorlds(mMemoryManager.getHeapAllocator()), mSphereShapes(mMemoryManager.getHeapAllocator()),
: mMemoryManager(baseMemoryAllocator),
mPhysicsWorlds(mMemoryManager.getHeapAllocator()), mSphereShapes(mMemoryManager.getHeapAllocator()),
mBoxShapes(mMemoryManager.getHeapAllocator()), mCapsuleShapes(mMemoryManager.getHeapAllocator()),
mConvexMeshShapes(mMemoryManager.getHeapAllocator()), mConcaveMeshShapes(mMemoryManager.getHeapAllocator()),
mHeightFieldShapes(mMemoryManager.getHeapAllocator()), mPolyhedronMeshes(mMemoryManager.getHeapAllocator()),
@ -49,14 +49,9 @@ PhysicsCommon::~PhysicsCommon() {
// Destroy and release everything that has been allocated
void PhysicsCommon::release() {
// Destroy the collision worlds
for (auto it = mCollisionWorlds.begin(); it != mCollisionWorlds.end(); ++it) {
destroyCollisionWorld(*it);
}
// Destroy the dynamics worlds
for (auto it = mDynamicsWorlds.begin(); it != mDynamicsWorlds.end(); ++it) {
destroyDynamicsWorld(*it);
// Destroy the physics worlds
for (auto it = mPhysicsWorlds.begin(); it != mPhysicsWorlds.end(); ++it) {
destroyPhysicsWorld(*it);
}
// Destroy the sphere shapes
@ -100,48 +95,26 @@ void PhysicsCommon::release() {
}
}
// Create and return an instance of CollisionWorld
CollisionWorld* PhysicsCommon::createCollisionWorld(const WorldSettings& worldSettings, Logger* logger, Profiler* profiler) {
// Create and return an instance of PhysicsWorld
PhysicsWorld* PhysicsCommon::createPhysicsWorld(const PhysicsWorld::WorldSettings& worldSettings, Logger* logger, Profiler* profiler) {
CollisionWorld* world = new(mMemoryManager.allocate(MemoryManager::AllocationType::Heap, sizeof(CollisionWorld))) CollisionWorld(mMemoryManager, worldSettings, logger, profiler);
mCollisionWorlds.add(world);
PhysicsWorld* world = new(mMemoryManager.allocate(MemoryManager::AllocationType::Heap, sizeof(PhysicsWorld))) PhysicsWorld(mMemoryManager, worldSettings, logger, profiler);
mPhysicsWorlds.add(world);
return world;
}
// Destroy an instance of CollisionWorld
void PhysicsCommon::destroyCollisionWorld(CollisionWorld* world) {
// Destroy an instance of PhysicsWorld
PhysicsWorld* PhysicsCommon::destroyPhysicsWorld(PhysicsWorld* world) {
// Call the destructor of the world
world->~CollisionWorld();
world->~PhysicsWorld();
// Release allocated memory
mMemoryManager.release(MemoryManager::AllocationType::Heap, world, sizeof(CollisionWorld));
mMemoryManager.release(MemoryManager::AllocationType::Heap, world, sizeof(PhysicsWorld));
mCollisionWorlds.remove(world);
}
// Create and return an instance of DynamicsWorld
DynamicsWorld* PhysicsCommon::createDynamicsWorld(const Vector3& gravity, const WorldSettings& worldSettings,
Logger* logger, Profiler* profiler) {
DynamicsWorld* world = new(mMemoryManager.allocate(MemoryManager::AllocationType::Heap, sizeof(DynamicsWorld))) DynamicsWorld(gravity, mMemoryManager, worldSettings, logger, profiler);
mDynamicsWorlds.add(world);
return world;
}
// Destroy an instance of DynamicsWorld
DynamicsWorld* PhysicsCommon::destroyDynamicsWorld(DynamicsWorld* world) {
// Call the destructor of the world
world->~DynamicsWorld();
// Release allocated memory
mMemoryManager.release(MemoryManager::AllocationType::Heap, world, sizeof(DynamicsWorld));
mDynamicsWorlds.remove(world);
mPhysicsWorlds.remove(world);
}
// Create and return a sphere collision shape

View File

@ -28,8 +28,7 @@
// Libraries
#include "memory/MemoryManager.h"
#include "engine/CollisionWorld.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
#include "collision/shapes/SphereShape.h"
#include "collision/shapes/BoxShape.h"
#include "collision/shapes/CapsuleShape.h"
@ -56,11 +55,8 @@ class PhysicsCommon {
/// Memory manager
MemoryManager mMemoryManager;
/// Set of collision worlds
Set<CollisionWorld*> mCollisionWorlds;
/// Set of dynamics worlds
Set<DynamicsWorld*> mDynamicsWorlds;
/// Set of physics worlds
Set<PhysicsWorld*> mPhysicsWorlds;
/// Set of sphere shapes
Set<SphereShape*> mSphereShapes;
@ -104,19 +100,12 @@ class PhysicsCommon {
/// Destructor
~PhysicsCommon();
/// Create and return an instance of CollisionWorld
CollisionWorld* createCollisionWorld(const WorldSettings& worldSettings = WorldSettings(), Logger* logger = nullptr,
Profiler* profiler = nullptr);
/// Destroy an instance of CollisionWorld
void destroyCollisionWorld(CollisionWorld* world);
/// Create and return an instance of DynamicsWorld
DynamicsWorld* createDynamicsWorld(const Vector3& gravity, const WorldSettings& worldSettings = WorldSettings(),
/// Create and return an instance of PhysicsWorld
PhysicsWorld* createPhysicsWorld(const PhysicsWorld::WorldSettings& worldSettings = PhysicsWorld::WorldSettings(),
Logger* logger = nullptr, Profiler* profiler = nullptr);
/// Destroy an instance of DynamicsWorld
DynamicsWorld* destroyDynamicsWorld(DynamicsWorld* world);
/// Destroy an instance of PhysicsWorld
PhysicsWorld* destroyPhysicsWorld(PhysicsWorld* world);
/// Create and return a sphere collision shape
SphereShape* createSphereShape(const decimal radius);

View File

@ -24,7 +24,7 @@
********************************************************************************/
// Libraries
#include "DynamicsWorld.h"
#include "PhysicsWorld.h"
#include "constraint/BallAndSocketJoint.h"
#include "constraint/SliderJoint.h"
#include "constraint/HingeJoint.h"
@ -32,7 +32,6 @@
#include "utils/Profiler.h"
#include "engine/EventListener.h"
#include "engine/Island.h"
#include "engine/Islands.h"
#include "collision/ContactManifold.h"
#include "containers/Stack.h"
@ -40,6 +39,10 @@
using namespace reactphysics3d;
using namespace std;
// Static initializations
uint PhysicsWorld::mNbWorlds = 0;
// Constructor
/**
* @param gravity Gravity vector in the world (in meters per second squared)
@ -47,38 +50,129 @@ using namespace std;
* @param logger Pointer to the logger
* @param profiler Pointer to the profiler
*/
DynamicsWorld::DynamicsWorld(const Vector3& gravity, MemoryManager& memoryManager, const WorldSettings& worldSettings, Logger* logger, Profiler* profiler)
: CollisionWorld(memoryManager, worldSettings, logger, profiler),
mIslands(mMemoryManager.getSingleFrameAllocator()),
PhysicsWorld::PhysicsWorld(MemoryManager& memoryManager, const WorldSettings& worldSettings, Logger* logger, Profiler* profiler)
: mMemoryManager(memoryManager), mConfig(worldSettings), mEntityManager(mMemoryManager.getHeapAllocator()),
mCollisionBodyComponents(mMemoryManager.getHeapAllocator()), mRigidBodyComponents(mMemoryManager.getHeapAllocator()),
mTransformComponents(mMemoryManager.getHeapAllocator()), mCollidersComponents(mMemoryManager.getHeapAllocator()),
mJointsComponents(mMemoryManager.getHeapAllocator()), mBallAndSocketJointsComponents(mMemoryManager.getHeapAllocator()),
mFixedJointsComponents(mMemoryManager.getHeapAllocator()), mHingeJointsComponents(mMemoryManager.getHeapAllocator()),
mSliderJointsComponents(mMemoryManager.getHeapAllocator()), mCollisionDetection(this, mCollidersComponents, mTransformComponents, mCollisionBodyComponents, mRigidBodyComponents,
mMemoryManager),
mBodies(mMemoryManager.getHeapAllocator()), mEventListener(nullptr),
mName(worldSettings.worldName), mIsProfilerCreatedByUser(profiler != nullptr),
mIsLoggerCreatedByUser(logger != nullptr), mIslands(mMemoryManager.getSingleFrameAllocator()),
mContactSolverSystem(mMemoryManager, *this, mIslands, mCollisionBodyComponents, mRigidBodyComponents,
mCollidersComponents, mConfig),
mCollidersComponents, mConfig.restitutionVelocityThreshold),
mConstraintSolverSystem(*this, mIslands, mRigidBodyComponents, mTransformComponents, mJointsComponents,
mBallAndSocketJointsComponents, mFixedJointsComponents, mHingeJointsComponents,
mSliderJointsComponents),
mDynamicsSystem(*this, mCollisionBodyComponents, mRigidBodyComponents, mTransformComponents, mCollidersComponents, mIsGravityEnabled, mGravity),
mDynamicsSystem(*this, mCollisionBodyComponents, mRigidBodyComponents, mTransformComponents, mCollidersComponents, mIsGravityEnabled, mConfig.gravity),
mNbVelocitySolverIterations(mConfig.defaultVelocitySolverNbIterations),
mNbPositionSolverIterations(mConfig.defaultPositionSolverNbIterations),
mIsSleepingEnabled(mConfig.isSleepingEnabled), mRigidBodies(mMemoryManager.getPoolAllocator()),
mGravity(gravity), mIsGravityEnabled(true), mSleepLinearVelocity(mConfig.defaultSleepLinearVelocity),
mIsGravityEnabled(true), mSleepLinearVelocity(mConfig.defaultSleepLinearVelocity),
mSleepAngularVelocity(mConfig.defaultSleepAngularVelocity), mTimeBeforeSleep(mConfig.defaultTimeBeforeSleep), mCurrentJointId(0) {
// Automatically generate a name for the world
if (mName == "") {
std::stringstream ss;
ss << "world";
if (mNbWorlds > 0) {
ss << mNbWorlds;
}
mName = ss.str();
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
mProfiler = profiler;
// If the user has not provided its own profiler, we create one
if (mProfiler == nullptr) {
mProfiler = new Profiler();
// Add a destination file for the profiling data
mProfiler->addFileDestination("rp3d_profiling_" + mName + ".txt", Profiler::Format::Text);
}
// Set the profiler
mConstraintSolverSystem.setProfiler(mProfiler);
mContactSolverSystem.setProfiler(mProfiler);
mDynamicsSystem.setProfiler(mProfiler);
mCollisionDetection.setProfiler(mProfiler);
#endif
#ifdef IS_LOGGING_ACTIVE
mLogger = logger;
// If the user has not provided its own logger, we create one
if (mLogger == nullptr) {
mLogger = new Logger();
// Add a log destination file
uint logLevel = static_cast<uint>(Logger::Level::Information) | static_cast<uint>(Logger::Level::Warning) |
static_cast<uint>(Logger::Level::Error);
mLogger->addFileDestination("rp3d_log_" + mName + ".html", logLevel, Logger::Format::HTML);
}
#endif
mNbWorlds++;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Dynamics World: Dynamics world " + mName + " has been created");
"Physics World: Physics world " + mName + " has been created");
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: Initial world settings: " + worldSettings.to_string());
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: Physics world " + mName + " has been created");
}
// Destructor
DynamicsWorld::~DynamicsWorld() {
PhysicsWorld::~PhysicsWorld() {
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: Physics world " + mName + " has been destroyed");
// Destroy all the collision bodies that have not been removed
for (int i=mBodies.size() - 1 ; i >= 0; i--) {
destroyCollisionBody(mBodies[i]);
}
#ifdef IS_PROFILING_ACTIVE
/// Delete the profiler
if (!mIsProfilerCreatedByUser) {
delete mProfiler;
}
// Print the profiling report into the destinations
mProfiler->printReport();
#endif
#ifdef IS_LOGGING_ACTIVE
/// Delete the logger
if (!mIsLoggerCreatedByUser) {
delete mLogger;
}
#endif
assert(mBodies.size() == 0);
assert(mCollisionBodyComponents.getNbComponents() == 0);
assert(mTransformComponents.getNbComponents() == 0);
assert(mCollidersComponents.getNbComponents() == 0);
// Destroy all the joints that have not been removed
for (uint32 i=0; i < mJointsComponents.getNbComponents(); i++) {
destroyJoint(mJointsComponents.mJoints[i]);
@ -92,28 +186,184 @@ DynamicsWorld::~DynamicsWorld() {
assert(mJointsComponents.getNbComponents() == 0);
assert(mRigidBodies.size() == 0);
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: Physics world " + mName + " has been destroyed");
}
// Create a collision body and add it to the world
/**
* @param transform Transformation mapping the local-space of the body to world-space
* @return A pointer to the body that has been created in the world
*/
CollisionBody* PhysicsWorld::createCollisionBody(const Transform& transform) {
// Create a new entity for the body
Entity entity = mEntityManager.createEntity();
mTransformComponents.addComponent(entity, false, TransformComponents::TransformComponent(transform));
// Create the collision body
CollisionBody* collisionBody = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool,
sizeof(CollisionBody)))
CollisionBody(*this, entity);
assert(collisionBody != nullptr);
// Add the components
CollisionBodyComponents::CollisionBodyComponent bodyComponent(collisionBody);
mCollisionBodyComponents.addComponent(entity, false, bodyComponent);
// Add the collision body to the world
mBodies.add(collisionBody);
#ifdef IS_PROFILING_ACTIVE
// Print the profiling report into the destinations
mProfiler->printReport();
collisionBody->setProfiler(mProfiler);
#endif
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Dynamics World: Dynamics world " + mName + " has been destroyed");
#ifdef IS_LOGGING_ACTIVE
collisionBody->setLogger(mLogger);
#endif
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body,
"Body " + std::to_string(entity.id) + ": New collision body created");
// Return the pointer to the rigid body
return collisionBody;
}
// Destroy a collision body
/**
* @param collisionBody Pointer to the body to destroy
*/
void PhysicsWorld::destroyCollisionBody(CollisionBody* collisionBody) {
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body,
"Body " + std::to_string(collisionBody->getEntity().id) + ": collision body destroyed");
// Remove all the collision shapes of the body
collisionBody->removeAllCollisionShapes();
mCollisionBodyComponents.removeComponent(collisionBody->getEntity());
mTransformComponents.removeComponent(collisionBody->getEntity());
mEntityManager.destroyEntity(collisionBody->getEntity());
// Call the destructor of the collision body
collisionBody->~CollisionBody();
// Remove the collision body from the list of bodies
mBodies.remove(collisionBody);
// Free the object from the memory allocator
mMemoryManager.release(MemoryManager::AllocationType::Pool, collisionBody, sizeof(CollisionBody));
}
// Notify the world if a body is disabled (sleeping) or not
void PhysicsWorld::setBodyDisabled(Entity bodyEntity, bool isDisabled) {
if (isDisabled == mCollisionBodyComponents.getIsEntityDisabled(bodyEntity)) return;
// Notify all the components
mCollisionBodyComponents.setIsEntityDisabled(bodyEntity, isDisabled);
mTransformComponents.setIsEntityDisabled(bodyEntity, isDisabled);
if (mRigidBodyComponents.hasComponent(bodyEntity)) {
mRigidBodyComponents.setIsEntityDisabled(bodyEntity, isDisabled);
}
// For each collider of the body
const List<Entity>& collidersEntities = mCollisionBodyComponents.getColliders(bodyEntity);
for (uint i=0; i < collidersEntities.size(); i++) {
mCollidersComponents.setIsEntityDisabled(collidersEntities[i], isDisabled);
}
// Disable the joints of the body if necessary
if (mRigidBodyComponents.hasComponent(bodyEntity)) {
// For each joint of the body
const List<Entity>& joints = mRigidBodyComponents.getJoints(bodyEntity);
for(uint32 i=0; i < joints.size(); i++) {
const Entity body1Entity = mJointsComponents.getBody1Entity(joints[i]);
const Entity body2Entity = mJointsComponents.getBody2Entity(joints[i]);
// If both bodies of the joint are disabled
if (mRigidBodyComponents.getIsEntityDisabled(body1Entity) &&
mRigidBodyComponents.getIsEntityDisabled(body2Entity)) {
// We disable the joint
setJointDisabled(joints[i], true);
}
else {
// Enable the joint
setJointDisabled(joints[i], false);
}
}
}
}
// Notify the world whether a joint is disabled or not
void PhysicsWorld::setJointDisabled(Entity jointEntity, bool isDisabled) {
if (isDisabled == mJointsComponents.getIsEntityDisabled(jointEntity)) return;
mJointsComponents.setIsEntityDisabled(jointEntity, isDisabled);
if (mBallAndSocketJointsComponents.hasComponent(jointEntity)) {
mBallAndSocketJointsComponents.setIsEntityDisabled(jointEntity, isDisabled);
}
if (mFixedJointsComponents.hasComponent(jointEntity)) {
mFixedJointsComponents.setIsEntityDisabled(jointEntity, isDisabled);
}
if (mHingeJointsComponents.hasComponent(jointEntity)) {
mHingeJointsComponents.setIsEntityDisabled(jointEntity, isDisabled);
}
if (mSliderJointsComponents.hasComponent(jointEntity)) {
mSliderJointsComponents.setIsEntityDisabled(jointEntity, isDisabled);
}
}
// Return true if two bodies overlap
/// Use this method if you are not interested in contacts but if you simply want to know
/// if the two bodies overlap. If you want to get the contacts, you need to use the
/// testCollision() method instead.
/**
* @param body1 Pointer to the first body
* @param body2 Pointer to a second body
* @return True if the two bodies overlap
*/
bool PhysicsWorld::testOverlap(CollisionBody* body1, CollisionBody* body2) {
return mCollisionDetection.testOverlap(body1, body2);
}
// Return the current world-space AABB of given collider
/**
* @param collider Pointer to a collider
* @return The AAABB of the collider in world-space
*/
AABB PhysicsWorld::getWorldAABB(const Collider* collider) const {
if (collider->getBroadPhaseId() == -1) {
return AABB();
}
return mCollisionDetection.getWorldAABB(collider);
}
// Update the physics simulation
/**
* @param timeStep The amount of time to step the simulation by (in seconds)
*/
void DynamicsWorld::update(decimal timeStep) {
void PhysicsWorld::update(decimal timeStep) {
#ifdef IS_PROFILING_ACTIVE
// Increment the frame counter of the profiler
mProfiler->incrementFrameCounter();
#endif
RP3D_PROFILE("DynamicsWorld::update()", mProfiler);
RP3D_PROFILE("PhysicsWorld::update()", mProfiler);
// Compute the collision detection
mCollisionDetection.computeCollisionDetection();
@ -159,9 +409,9 @@ void DynamicsWorld::update(decimal timeStep) {
// Solve the contacts and constraints
void DynamicsWorld::solveContactsAndConstraints(decimal timeStep) {
void PhysicsWorld::solveContactsAndConstraints(decimal timeStep) {
RP3D_PROFILE("DynamicsWorld::solveContactsAndConstraints()", mProfiler);
RP3D_PROFILE("PhysicsWorld::solveContactsAndConstraints()", mProfiler);
// ---------- Solve velocity constraints for joints and contacts ---------- //
@ -186,9 +436,9 @@ void DynamicsWorld::solveContactsAndConstraints(decimal timeStep) {
}
// Solve the position error correction of the constraints
void DynamicsWorld::solvePositionCorrection() {
void PhysicsWorld::solvePositionCorrection() {
RP3D_PROFILE("DynamicsWorld::solvePositionCorrection()", mProfiler);
RP3D_PROFILE("PhysicsWorld::solvePositionCorrection()", mProfiler);
// ---------- Solve the position error correction for the constraints ---------- //
@ -201,7 +451,7 @@ void DynamicsWorld::solvePositionCorrection() {
}
// Disable the joints for pair of sleeping bodies
void DynamicsWorld::disableJointsOfSleepingBodies() {
void PhysicsWorld::disableJointsOfSleepingBodies() {
// For each joint
for (uint32 i=0; i < mJointsComponents.getNbEnabledComponents(); i++) {
@ -223,7 +473,7 @@ void DynamicsWorld::disableJointsOfSleepingBodies() {
* @param transform Transformation from body local-space to world-space
* @return A pointer to the body that has been created in the world
*/
RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) {
RigidBody* PhysicsWorld::createRigidBody(const Transform& transform) {
// Create a new entity for the body
Entity entity = mEntityManager.createEntity();
@ -267,7 +517,7 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) {
/**
* @param rigidBody Pointer to the body you want to destroy
*/
void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) {
void PhysicsWorld::destroyRigidBody(RigidBody* rigidBody) {
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body,
"Body " + std::to_string(rigidBody->getEntity().id) + ": rigid body destroyed");
@ -303,7 +553,7 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) {
* @param jointInfo The information that is necessary to create the joint
* @return A pointer to the joint that has been created in the world
*/
Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) {
Joint* PhysicsWorld::createJoint(const JointInfo& jointInfo) {
// Create a new entity for the joint
Entity entity = mEntityManager.createEntity();
@ -426,7 +676,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) {
/**
* @param joint Pointer to the joint you want to destroy
*/
void DynamicsWorld::destroyJoint(Joint* joint) {
void PhysicsWorld::destroyJoint(Joint* joint) {
assert(joint != nullptr);
@ -479,7 +729,7 @@ void DynamicsWorld::destroyJoint(Joint* joint) {
}
// Add the joint to the list of joints of the two bodies involved in the joint
void DynamicsWorld::addJointToBodies(Entity body1, Entity body2, Entity joint) {
void PhysicsWorld::addJointToBodies(Entity body1, Entity body2, Entity joint) {
mRigidBodyComponents.addJointToBody(body1, joint);
@ -502,12 +752,12 @@ void DynamicsWorld::addJointToBodies(Entity body1, Entity body2, Entity joint) {
/// (graph where nodes are the bodies and where the edges are the constraints between the bodies) to
/// find all the bodies that are connected with it (the bodies that share joints or contacts with
/// it). Then, we create an island with this group of connected bodies.
void DynamicsWorld::createIslands() {
void PhysicsWorld::createIslands() {
// list of contact pairs involving a non-rigid body
List<uint> nonRigidBodiesContactPairs(mMemoryManager.getSingleFrameAllocator());
RP3D_PROFILE("DynamicsWorld::createIslands()", mProfiler);
RP3D_PROFILE("PhysicsWorld::createIslands()", mProfiler);
// Reset all the isAlreadyInIsland variables of bodies and joints
for (uint b=0; b < mRigidBodyComponents.getNbComponents(); b++) {
@ -640,9 +890,9 @@ void DynamicsWorld::createIslands() {
// Put bodies to sleep if needed.
/// For each island, if all the bodies have been almost still for a long enough period of
/// time, we put all the bodies of the island to sleep.
void DynamicsWorld::updateSleepingBodies(decimal timeStep) {
void PhysicsWorld::updateSleepingBodies(decimal timeStep) {
RP3D_PROFILE("DynamicsWorld::updateSleepingBodies()", mProfiler);
RP3D_PROFILE("PhysicsWorld::updateSleepingBodies()", mProfiler);
const decimal sleepLinearVelocitySquare = mSleepLinearVelocity * mSleepLinearVelocity;
const decimal sleepAngularVelocitySquare = mSleepAngularVelocity * mSleepAngularVelocity;
@ -704,7 +954,7 @@ void DynamicsWorld::updateSleepingBodies(decimal timeStep) {
* @param isSleepingEnabled True if you want to enable the sleeping technique
* and false otherwise
*/
void DynamicsWorld::enableSleeping(bool isSleepingEnabled) {
void PhysicsWorld::enableSleeping(bool isSleepingEnabled) {
mIsSleepingEnabled = isSleepingEnabled;
if (!mIsSleepingEnabled) {
@ -719,5 +969,5 @@ void DynamicsWorld::enableSleeping(bool isSleepingEnabled) {
}
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Dynamics World: isSleepingEnabled=" + (isSleepingEnabled ? std::string("true") : std::string("false")) );
"Physics World: isSleepingEnabled=" + (isSleepingEnabled ? std::string("true") : std::string("false")) );
}

786
src/engine/PhysicsWorld.h Normal file
View File

@ -0,0 +1,786 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2019 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_PHYSICS_WORLD_H
#define REACTPHYSICS3D_PHYSICS_WORLD_H
// Libraries
#include "mathematics/mathematics.h"
#include "containers/List.h"
#include "constraint/Joint.h"
#include "memory/MemoryManager.h"
#include "engine/EntityManager.h"
#include "components/CollisionBodyComponents.h"
#include "components/RigidBodyComponents.h"
#include "components/TransformComponents.h"
#include "components/ColliderComponents.h"
#include "components/JointComponents.h"
#include "components/BallAndSocketJointComponents.h"
#include "components/FixedJointComponents.h"
#include "components/HingeJointComponents.h"
#include "components/SliderJointComponents.h"
#include "collision/CollisionCallback.h"
#include "collision/OverlapCallback.h"
#include "configuration.h"
#include "utils/Logger.h"
#include "systems/ConstraintSolverSystem.h"
#include "systems/CollisionDetectionSystem.h"
#include "systems/ContactSolverSystem.h"
#include "systems/DynamicsSystem.h"
#include "engine/Islands.h"
#include <sstream>
/// Namespace ReactPhysics3D
namespace reactphysics3d {
// Declarations
class Island;
class RigidBody;
struct JointInfo;
// Class PhysicsWorld
/**
* This class represents a physics world.
*/
class PhysicsWorld {
public:
/// Structure WorldSettings
/**
* This class is used to describe some settings of a physics world.
*/
struct WorldSettings {
/// Name of the world
std::string worldName;
/// Gravity vector of the world
Vector3 gravity;
/// Distance threshold for two contact points for a valid persistent contact (in meters)
decimal persistentContactDistanceThreshold;
/// Default friction coefficient for a rigid body
decimal defaultFrictionCoefficient;
/// Default bounciness factor for a rigid body
decimal defaultBounciness;
/// Velocity threshold for contact velocity restitution
decimal restitutionVelocityThreshold;
/// Default rolling resistance
decimal defaultRollingRestistance;
/// True if the sleeping technique is enabled
bool isSleepingEnabled;
/// Number of iterations when solving the velocity constraints of the Sequential Impulse technique
uint defaultVelocitySolverNbIterations;
/// Number of iterations when solving the position constraints of the Sequential Impulse technique
uint defaultPositionSolverNbIterations;
/// Time (in seconds) that a body must stay still to be considered sleeping
float defaultTimeBeforeSleep;
/// A body with a linear velocity smaller than the sleep linear velocity (in m/s)
/// might enter sleeping mode.
decimal defaultSleepLinearVelocity;
/// A body with angular velocity smaller than the sleep angular velocity (in rad/s)
/// might enter sleeping mode
decimal defaultSleepAngularVelocity;
/// Maximum number of contact manifolds in an overlapping pair
uint nbMaxContactManifolds;
/// 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;
WorldSettings() {
worldName = "";
gravity = Vector3(0, decimal(-9.81), 0);
persistentContactDistanceThreshold = decimal(0.03);
defaultFrictionCoefficient = decimal(0.3);
defaultBounciness = decimal(0.5);
restitutionVelocityThreshold = decimal(0.5);
defaultRollingRestistance = decimal(0.0);
isSleepingEnabled = true;
defaultVelocitySolverNbIterations = 10;
defaultPositionSolverNbIterations = 5;
defaultTimeBeforeSleep = 1.0f;
defaultSleepLinearVelocity = decimal(0.02);
defaultSleepAngularVelocity = decimal(3.0) * (PI / decimal(180.0));
nbMaxContactManifolds = 3;
cosAngleSimilarContactManifold = decimal(0.95);
}
~WorldSettings() = default;
/// Return a string with the world settings
std::string to_string() const {
std::stringstream ss;
ss << "worldName=" << worldName << std::endl;
ss << "gravity=" << gravity.to_string() << std::endl;
ss << "persistentContactDistanceThreshold=" << persistentContactDistanceThreshold << std::endl;
ss << "defaultFrictionCoefficient=" << defaultFrictionCoefficient << std::endl;
ss << "defaultBounciness=" << defaultBounciness << std::endl;
ss << "restitutionVelocityThreshold=" << restitutionVelocityThreshold << std::endl;
ss << "defaultRollingRestistance=" << defaultRollingRestistance << std::endl;
ss << "isSleepingEnabled=" << isSleepingEnabled << std::endl;
ss << "defaultVelocitySolverNbIterations=" << defaultVelocitySolverNbIterations << std::endl;
ss << "defaultPositionSolverNbIterations=" << defaultPositionSolverNbIterations << std::endl;
ss << "defaultTimeBeforeSleep=" << defaultTimeBeforeSleep << std::endl;
ss << "defaultSleepLinearVelocity=" << defaultSleepLinearVelocity << std::endl;
ss << "defaultSleepAngularVelocity=" << defaultSleepAngularVelocity << std::endl;
ss << "nbMaxContactManifolds=" << nbMaxContactManifolds << std::endl;
ss << "cosAngleSimilarContactManifold=" << cosAngleSimilarContactManifold << std::endl;
return ss.str();
}
};
protected :
// -------------------- Attributes -------------------- //
/// Memory manager
MemoryManager& mMemoryManager;
/// Configuration of the physics world
WorldSettings mConfig;
/// Entity Manager for the ECS
EntityManager mEntityManager;
/// Collision Body Components
CollisionBodyComponents mCollisionBodyComponents;
/// Rigid Body Components
RigidBodyComponents mRigidBodyComponents;
/// Transform Components
TransformComponents mTransformComponents;
/// Collider Components
ColliderComponents mCollidersComponents;
/// Joint Components
JointComponents mJointsComponents;
/// Ball And Socket joints Components
BallAndSocketJointComponents mBallAndSocketJointsComponents;
/// Fixed joints Components
FixedJointComponents mFixedJointsComponents;
/// Hinge joints Components
HingeJointComponents mHingeJointsComponents;
/// Slider joints Components
SliderJointComponents mSliderJointsComponents;
/// Reference to the collision detection
CollisionDetectionSystem mCollisionDetection;
/// All the bodies (rigid and soft) of the world
List<CollisionBody*> mBodies;
/// Pointer to an event listener object
EventListener* mEventListener;
/// Name of the physics world
std::string mName;
#ifdef IS_PROFILING_ACTIVE
/// Real-time hierarchical profiler
Profiler* mProfiler;
#endif
#ifdef IS_LOGGING_ACTIVE
/// Logger
Logger* mLogger;
#endif
/// True if the profiler has been created by the user
bool mIsProfilerCreatedByUser;
/// True if the logger has been created by the user
bool mIsLoggerCreatedByUser;
/// Total number of worlds
static uint mNbWorlds;
/// All the islands of bodies of the current frame
Islands mIslands;
/// Contact solver system
ContactSolverSystem mContactSolverSystem;
/// Constraint solver system
ConstraintSolverSystem mConstraintSolverSystem;
/// Dynamics system
DynamicsSystem mDynamicsSystem;
/// Number of iterations for the velocity solver of the Sequential Impulses technique
uint mNbVelocitySolverIterations;
/// Number of iterations for the position solver of the Sequential Impulses technique
uint mNbPositionSolverIterations;
/// True if the spleeping technique for inactive bodies is enabled
bool mIsSleepingEnabled;
/// All the rigid bodies of the physics world
List<RigidBody*> mRigidBodies;
/// True if the gravity force is on
bool mIsGravityEnabled;
/// Sleep linear velocity threshold
decimal mSleepLinearVelocity;
/// Sleep angular velocity threshold
decimal mSleepAngularVelocity;
/// Time (in seconds) before a body is put to sleep if its velocity
/// becomes smaller than the sleep velocity.
decimal mTimeBeforeSleep;
/// Current joint id
uint mCurrentJointId;
// -------------------- Methods -------------------- //
/// Constructor
PhysicsWorld(MemoryManager& memoryManager, const WorldSettings& worldSettings = WorldSettings(),
Logger* logger = nullptr, Profiler* profiler = nullptr);
/// Notify the world if a body is disabled (slepping or inactive) or not
void setBodyDisabled(Entity entity, bool isDisabled);
/// Notify the world whether a joint is disabled or not
void setJointDisabled(Entity jointEntity, bool isDisabled);
/// Solve the contacts and constraints
void solveContactsAndConstraints(decimal timeStep);
/// Solve the position error correction of the constraints
void solvePositionCorrection();
/// Compute the islands of awake bodies.
void computeIslands();
/// Compute the islands using potential contacts and joints and create the actual contacts.
void createIslands();
/// Put bodies to sleep if needed.
void updateSleepingBodies(decimal timeStep);
/// Add the joint to the list of joints of the two bodies involved in the joint
void addJointToBodies(Entity body1, Entity body2, Entity joint);
/// Destructor
~PhysicsWorld();
public :
// -------------------- Methods -------------------- //
/// Create a collision body
CollisionBody* createCollisionBody(const Transform& transform);
/// Destroy a collision body
void destroyCollisionBody(CollisionBody* collisionBody);
/// Get the collision dispatch configuration
CollisionDispatch& getCollisionDispatch();
/// Ray cast method
void raycast(const Ray& ray, RaycastCallback* raycastCallback, unsigned short raycastWithCategoryMaskBits = 0xFFFF) const;
/// Return true if two bodies overlap (collide)
bool testOverlap(CollisionBody* body1, CollisionBody* body2);
/// Report all the bodies that overlap (collide) with the body in parameter
void testOverlap(CollisionBody* body, OverlapCallback& overlapCallback);
/// Report all the bodies that overlap (collide) in the world
void testOverlap(OverlapCallback& overlapCallback);
/// Test collision and report contacts between two bodies.
void testCollision(CollisionBody* body1, CollisionBody* body2, CollisionCallback& callback);
/// Test collision and report all the contacts involving the body in parameter
void testCollision(CollisionBody* body, CollisionCallback& callback);
/// Test collision and report contacts between each colliding bodies in the world
void testCollision(CollisionCallback& callback);
/// Return a reference to the memory manager of the world
MemoryManager& getMemoryManager();
/// Return the current world-space AABB of given collider
AABB getWorldAABB(const Collider* collider) const;
/// Return the name of the world
const std::string& getName() const;
/// Deleted copy-constructor
PhysicsWorld(const PhysicsWorld& world) = delete;
/// Deleted assignment operator
PhysicsWorld& operator=(const PhysicsWorld& world) = delete;
/// Update the physics simulation
void update(decimal timeStep);
/// Get the number of iterations for the velocity constraint solver
uint getNbIterationsVelocitySolver() const;
/// Set the number of iterations for the velocity constraint solver
void setNbIterationsVelocitySolver(uint nbIterations);
/// Get the number of iterations for the position constraint solver
uint getNbIterationsPositionSolver() const;
/// Set the number of iterations for the position constraint solver
void setNbIterationsPositionSolver(uint nbIterations);
/// Set the position correction technique used for contacts
void setContactsPositionCorrectionTechnique(ContactsPositionCorrectionTechnique technique);
/// Set the position correction technique used for joints
void setJointsPositionCorrectionTechnique(JointsPositionCorrectionTechnique technique);
/// Create a rigid body into the physics world.
RigidBody* createRigidBody(const Transform& transform);
/// Disable the joints for pair of sleeping bodies
void disableJointsOfSleepingBodies();
/// Destroy a rigid body and all the joints which it belongs
void destroyRigidBody(RigidBody* rigidBody);
/// Create a joint between two bodies in the world and return a pointer to the new joint
Joint* createJoint(const JointInfo& jointInfo);
/// Destroy a joint
void destroyJoint(Joint* joint);
/// Return the gravity vector of the world
Vector3 getGravity() const;
/// Set the gravity vector of the world
void setGravity(Vector3& gravity);
/// Return if the gravity is on
bool isGravityEnabled() const;
/// Enable/Disable the gravity
void setIsGratityEnabled(bool isGravityEnabled);
/// Return true if the sleeping technique is enabled
bool isSleepingEnabled() const;
/// Enable/Disable the sleeping technique
void enableSleeping(bool isSleepingEnabled);
/// Return the current sleep linear velocity
decimal getSleepLinearVelocity() const;
/// Set the sleep linear velocity.
void setSleepLinearVelocity(decimal sleepLinearVelocity);
/// Return the current sleep angular velocity
decimal getSleepAngularVelocity() const;
/// Set the sleep angular velocity.
void setSleepAngularVelocity(decimal sleepAngularVelocity);
/// Return the time a body is required to stay still before sleeping
decimal getTimeBeforeSleep() const;
/// Set the time a body is required to stay still before sleeping
void setTimeBeforeSleep(decimal timeBeforeSleep);
/// Set an event listener object to receive events callbacks.
void setEventListener(EventListener* eventListener);
#ifdef IS_PROFILING_ACTIVE
/// Return a reference to the profiler
Profiler* getProfiler();
#endif
#ifdef IS_LOGGING_ACTIVE
/// Return a reference to the logger
Logger* getLogger();
#endif
// -------------------- Friendship -------------------- //
friend class CollisionDetectionSystem;
friend class CollisionBody;
friend class Collider;
friend class ConvexMeshShape;
friend class CollisionCallback::ContactPair;
friend class OverlapCallback::OverlapPair;
friend class PhysicsCommon;
friend class RigidBody;
friend class Joint;
friend class BallAndSocketJoint;
friend class FixedJoint;
friend class HingeJoint;
friend class SliderJoint;
};
// Set the collision dispatch configuration
/// This can be used to replace default collision detection algorithms by your
/// custom algorithm for instance.
/**
* @param CollisionDispatch Pointer to a collision dispatch object describing
* which collision detection algorithm to use for two given collision shapes
*/
inline CollisionDispatch& PhysicsWorld::getCollisionDispatch() {
return mCollisionDetection.getCollisionDispatch();
}
// Ray cast method
/**
* @param ray Ray to use for raycasting
* @param raycastCallback Pointer to the class with the callback method
* @param raycastWithCategoryMaskBits Bits mask corresponding to the category of
* bodies to be raycasted
*/
inline void PhysicsWorld::raycast(const Ray& ray,
RaycastCallback* raycastCallback,
unsigned short raycastWithCategoryMaskBits) const {
mCollisionDetection.raycast(raycastCallback, ray, raycastWithCategoryMaskBits);
}
// Test collision and report contacts between two bodies.
/// Use this method if you only want to get all the contacts between two bodies.
/// All the contacts will be reported using the callback object in paramater.
/// If you are not interested in the contacts but you only want to know if the bodies collide,
/// you can use the testOverlap() method instead.
/**
* @param body1 Pointer to the first body to test
* @param body2 Pointer to the second body to test
* @param callback Pointer to the object with the callback method
*/
inline void PhysicsWorld::testCollision(CollisionBody* body1, CollisionBody* body2, CollisionCallback& callback) {
mCollisionDetection.testCollision(body1, body2, callback);
}
// Test collision and report all the contacts involving the body in parameter
/// Use this method if you only want to get all the contacts involving a given body.
/// All the contacts will be reported using the callback object in paramater.
/// If you are not interested in the contacts but you only want to know if the bodies collide,
/// you can use the testOverlap() method instead.
/**
* @param body Pointer to the body against which we need to test collision
* @param callback Pointer to the object with the callback method to report contacts
*/
inline void PhysicsWorld::testCollision(CollisionBody* body, CollisionCallback& callback) {
mCollisionDetection.testCollision(body, callback);
}
// Test collision and report contacts between each colliding bodies in the world
/// Use this method if you want to get all the contacts between colliding bodies in the world.
/// All the contacts will be reported using the callback object in paramater.
/// If you are not interested in the contacts but you only want to know if the bodies collide,
/// you can use the testOverlap() method instead.
/**
* @param callback Pointer to the object with the callback method to report contacts
*/
inline void PhysicsWorld::testCollision(CollisionCallback& callback) {
mCollisionDetection.testCollision(callback);
}
// Report all the bodies that overlap (collide) with the body in parameter
/// Use this method if you are not interested in contacts but if you simply want to know
/// which bodies overlap with the body in parameter. If you want to get the contacts, you need to use the
/// testCollision() method instead.
/**
* @param body Pointer to the collision body to test overlap with
* @param overlapCallback Pointer to the callback class to report overlap
*/
inline void PhysicsWorld::testOverlap(CollisionBody* body, OverlapCallback& overlapCallback) {
mCollisionDetection.testOverlap(body, overlapCallback);
}
// Report all the bodies that overlap (collide) in the world
/// Use this method if you are not interested in contacts but if you simply want to know
/// which bodies overlap. If you want to get the contacts, you need to use the
/// testCollision() method instead.
inline void PhysicsWorld::testOverlap(OverlapCallback& overlapCallback) {
mCollisionDetection.testOverlap(overlapCallback);
}
// Return a reference to the memory manager of the world
inline MemoryManager& PhysicsWorld::getMemoryManager() {
return mMemoryManager;
}
// Return the name of the world
/**
* @return Name of the world
*/
inline const std::string& PhysicsWorld::getName() const {
return mName;
}
#ifdef IS_PROFILING_ACTIVE
// Return a pointer to the profiler
/**
* @return A pointer to the profiler
*/
inline Profiler* PhysicsWorld::getProfiler() {
return mProfiler;
}
#endif
#ifdef IS_LOGGING_ACTIVE
// Return a pointer to the logger
/**
* @return A pointer to the logger
*/
inline Logger* PhysicsWorld::getLogger() {
return mLogger;
}
#endif
// Get the number of iterations for the velocity constraint solver
/**
* @return The number of iterations of the velocity constraint solver
*/
inline uint PhysicsWorld::getNbIterationsVelocitySolver() const {
return mNbVelocitySolverIterations;
}
// Set the number of iterations for the velocity constraint solver
/**
* @param nbIterations Number of iterations for the velocity solver
*/
inline void PhysicsWorld::setNbIterationsVelocitySolver(uint nbIterations) {
mNbVelocitySolverIterations = nbIterations;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: Set nb iterations velocity solver to " + std::to_string(nbIterations));
}
// Get the number of iterations for the position constraint solver
/**
* @return The number of iterations of the position constraint solver
*/
inline uint PhysicsWorld::getNbIterationsPositionSolver() const {
return mNbPositionSolverIterations;
}
// Set the number of iterations for the position constraint solver
/**
* @param nbIterations Number of iterations for the position solver
*/
inline void PhysicsWorld::setNbIterationsPositionSolver(uint nbIterations) {
mNbPositionSolverIterations = nbIterations;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: Set nb iterations position solver to " + std::to_string(nbIterations));
}
// Set the position correction technique used for contacts
/**
* @param technique Technique used for the position correction (Baumgarte or Split Impulses)
*/
inline void PhysicsWorld::setContactsPositionCorrectionTechnique(
ContactsPositionCorrectionTechnique technique) {
if (technique == ContactsPositionCorrectionTechnique::BAUMGARTE_CONTACTS) {
mContactSolverSystem.setIsSplitImpulseActive(false);
}
else {
mContactSolverSystem.setIsSplitImpulseActive(true);
}
}
// Set the position correction technique used for joints
/**
* @param technique Technique used for the joins position correction (Baumgarte or Non Linear Gauss Seidel)
*/
inline void PhysicsWorld::setJointsPositionCorrectionTechnique(
JointsPositionCorrectionTechnique technique) {
if (technique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) {
mConstraintSolverSystem.setIsNonLinearGaussSeidelPositionCorrectionActive(false);
}
else {
mConstraintSolverSystem.setIsNonLinearGaussSeidelPositionCorrectionActive(true);
}
}
// Return the gravity vector of the world
/**
* @return The current gravity vector (in meter per seconds squared)
*/
inline Vector3 PhysicsWorld::getGravity() const {
return mConfig.gravity;
}
// Set the gravity vector of the world
/**
* @param gravity The gravity vector (in meter per seconds squared)
*/
inline void PhysicsWorld::setGravity(Vector3& gravity) {
mConfig.gravity = gravity;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: Set gravity vector to " + gravity.to_string());
}
// Return if the gravity is enaled
/**
* @return True if the gravity is enabled in the world
*/
inline bool PhysicsWorld::isGravityEnabled() const {
return mIsGravityEnabled;
}
// Enable/Disable the gravity
/**
* @param isGravityEnabled True if you want to enable the gravity in the world
* and false otherwise
*/
inline void PhysicsWorld::setIsGratityEnabled(bool isGravityEnabled) {
mIsGravityEnabled = isGravityEnabled;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: isGravityEnabled= " + (isGravityEnabled ? std::string("true") : std::string("false")));
}
// Return true if the sleeping technique is enabled
/**
* @return True if the sleeping technique is enabled and false otherwise
*/
inline bool PhysicsWorld::isSleepingEnabled() const {
return mIsSleepingEnabled;
}
// Return the current sleep linear velocity
/**
* @return The sleep linear velocity (in meters per second)
*/
inline decimal PhysicsWorld::getSleepLinearVelocity() const {
return mSleepLinearVelocity;
}
// Set the sleep linear velocity.
/// When the velocity of a body becomes smaller than the sleep linear/angular
/// velocity for a given amount of time, the body starts sleeping and does not need
/// to be simulated anymore.
/**
* @param sleepLinearVelocity The sleep linear velocity (in meters per second)
*/
inline void PhysicsWorld::setSleepLinearVelocity(decimal sleepLinearVelocity) {
assert(sleepLinearVelocity >= decimal(0.0));
mSleepLinearVelocity = sleepLinearVelocity;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: sleepLinearVelocity= " + std::to_string(sleepLinearVelocity));
}
// Return the current sleep angular velocity
/**
* @return The sleep angular velocity (in radian per second)
*/
inline decimal PhysicsWorld::getSleepAngularVelocity() const {
return mSleepAngularVelocity;
}
// Set the sleep angular velocity.
/// When the velocity of a body becomes smaller than the sleep linear/angular
/// velocity for a given amount of time, the body starts sleeping and does not need
/// to be simulated anymore.
/**
* @param sleepAngularVelocity The sleep angular velocity (in radian per second)
*/
inline void PhysicsWorld::setSleepAngularVelocity(decimal sleepAngularVelocity) {
assert(sleepAngularVelocity >= decimal(0.0));
mSleepAngularVelocity = sleepAngularVelocity;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: sleepAngularVelocity= " + std::to_string(sleepAngularVelocity));
}
// Return the time a body is required to stay still before sleeping
/**
* @return Time a body is required to stay still before sleeping (in seconds)
*/
inline decimal PhysicsWorld::getTimeBeforeSleep() const {
return mTimeBeforeSleep;
}
// Set the time a body is required to stay still before sleeping
/**
* @param timeBeforeSleep Time a body is required to stay still before sleeping (in seconds)
*/
inline void PhysicsWorld::setTimeBeforeSleep(decimal timeBeforeSleep) {
assert(timeBeforeSleep >= decimal(0.0));
mTimeBeforeSleep = timeBeforeSleep;
RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World,
"Physics World: timeBeforeSleep= " + std::to_string(timeBeforeSleep));
}
// Set an event listener object to receive events callbacks.
/// If you use "nullptr" as an argument, the events callbacks will be disabled.
/**
* @param eventListener Pointer to the event listener object that will receive
* event callbacks during the simulation
*/
inline void PhysicsWorld::setEventListener(EventListener* eventListener) {
mEventListener = eventListener;
}
}
#endif

View File

@ -40,8 +40,7 @@
#include "body/CollisionBody.h"
#include "body/RigidBody.h"
#include "engine/PhysicsCommon.h"
#include "engine/DynamicsWorld.h"
#include "engine/CollisionWorld.h"
#include "engine/PhysicsWorld.h"
#include "engine/Material.h"
#include "engine/EventListener.h"
#include "collision/shapes/CollisionShape.h"

View File

@ -29,7 +29,7 @@
#include "utils/Profiler.h"
#include "collision/RaycastInfo.h"
#include "memory/MemoryManager.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;

View File

@ -25,7 +25,7 @@
// Libraries
#include "systems/CollisionDetectionSystem.h"
#include "engine/CollisionWorld.h"
#include "engine/PhysicsWorld.h"
#include "collision/OverlapCallback.h"
#include "collision/shapes/BoxShape.h"
#include "collision/shapes/ConcaveShape.h"
@ -40,7 +40,6 @@
#include "utils/Profiler.h"
#include "engine/EventListener.h"
#include "collision/RaycastInfo.h"
#include "engine/Islands.h"
#include "containers/Pair.h"
#include <cassert>
#include <iostream>
@ -49,9 +48,8 @@
using namespace reactphysics3d;
using namespace std;
// Constructor
CollisionDetectionSystem::CollisionDetectionSystem(CollisionWorld* world, ColliderComponents& collidersComponents, TransformComponents& transformComponents,
CollisionDetectionSystem::CollisionDetectionSystem(PhysicsWorld* world, ColliderComponents& collidersComponents, TransformComponents& transformComponents,
CollisionBodyComponents& collisionBodyComponents, RigidBodyComponents& rigidBodyComponents, MemoryManager& memoryManager)
: mMemoryManager(memoryManager), mCollidersComponents(collidersComponents),
mCollisionDispatch(mMemoryManager.getPoolAllocator()), mWorld(world),
@ -687,7 +685,7 @@ void CollisionDetectionSystem::createContacts() {
ContactPointInfo& potentialContactPoint = mPotentialContactPoints[potentialManifold.potentialContactPointsIndices[c]];
// Create a new contact point
ContactPoint contactPoint(potentialContactPoint, mWorld->mConfig);
ContactPoint contactPoint(potentialContactPoint, mWorld->mConfig.persistentContactDistanceThreshold);
// Add the contact point
mCurrentContactPoints->add(contactPoint);
@ -755,7 +753,7 @@ void CollisionDetectionSystem::createSnapshotContacts(List<ContactPair>& contact
ContactPointInfo& potentialContactPoint = potentialContactPoints[potentialManifold.potentialContactPointsIndices[c]];
// Create a new contact point
ContactPoint contactPoint(potentialContactPoint, mWorld->mConfig);
ContactPoint contactPoint(potentialContactPoint, mWorld->mConfig.persistentContactDistanceThreshold);
// Add the contact point
contactPoints.add(contactPoint);

View File

@ -48,7 +48,7 @@
namespace reactphysics3d {
// Declarations
class CollisionWorld;
class PhysicsWorld;
class CollisionCallback;
class OverlapCallback;
class RaycastCallback;
@ -87,7 +87,7 @@ class CollisionDetectionSystem {
CollisionDispatch mCollisionDispatch;
/// Pointer to the physics world
CollisionWorld* mWorld;
PhysicsWorld* mWorld;
/// Set of pair of bodies that cannot collide between each other
Set<bodypair> mNoCollisionPairs;
@ -267,7 +267,7 @@ class CollisionDetectionSystem {
// -------------------- Methods -------------------- //
/// Constructor
CollisionDetectionSystem(CollisionWorld* world, ColliderComponents& collidersComponents,
CollisionDetectionSystem(PhysicsWorld* world, ColliderComponents& collidersComponents,
TransformComponents& transformComponents, CollisionBodyComponents& collisionBodyComponents, RigidBodyComponents& rigidBodyComponents,
MemoryManager& memoryManager);
@ -339,7 +339,7 @@ class CollisionDetectionSystem {
MemoryManager& getMemoryManager() const;
/// Return a pointer to the world
CollisionWorld* getWorld();
PhysicsWorld* getWorld();
/// Return the world event listener
EventListener* getWorldEventListener();
@ -356,7 +356,7 @@ class CollisionDetectionSystem {
// -------------------- Friendship -------------------- //
friend class DynamicsWorld;
friend class PhysicsWorld;
friend class ConvexMeshShape;
friend class RigidBody;
};
@ -401,7 +401,7 @@ inline void CollisionDetectionSystem::askForBroadPhaseCollisionCheck(Collider* s
}
// Return a pointer to the world
inline CollisionWorld* CollisionDetectionSystem::getWorld() {
inline PhysicsWorld* CollisionDetectionSystem::getWorld() {
return mWorld;
}

View File

@ -33,7 +33,7 @@
using namespace reactphysics3d;
// Constructor
ConstraintSolverSystem::ConstraintSolverSystem(DynamicsWorld& world, Islands& islands, RigidBodyComponents& rigidBodyComponents,
ConstraintSolverSystem::ConstraintSolverSystem(PhysicsWorld& world, Islands& islands, RigidBodyComponents& rigidBodyComponents,
TransformComponents& transformComponents,
JointComponents& jointComponents,
BallAndSocketJointComponents& ballAndSocketJointComponents,

View File

@ -29,7 +29,6 @@
// Libraries
#include "configuration.h"
#include "mathematics/mathematics.h"
#include "engine/Islands.h"
#include "systems/SolveBallAndSocketJointSystem.h"
#include "systems/SolveFixedJointSystem.h"
#include "systems/SolveHingeJointSystem.h"
@ -40,6 +39,7 @@ namespace reactphysics3d {
// Declarations
class Joint;
class Island;
struct Islands;
class Profiler;
class RigidBodyComponents;
class JointComponents;
@ -184,7 +184,7 @@ class ConstraintSolverSystem {
// -------------------- Methods -------------------- //
/// Constructor
ConstraintSolverSystem(DynamicsWorld& world, Islands& islands, RigidBodyComponents& rigidBodyComponents,
ConstraintSolverSystem(PhysicsWorld& world, Islands& islands, RigidBodyComponents& rigidBodyComponents,
TransformComponents& transformComponents,
JointComponents& jointComponents,
BallAndSocketJointComponents& ballAndSocketJointComponents,

View File

@ -25,7 +25,7 @@
// Libraries
#include "systems/ContactSolverSystem.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
#include "body/RigidBody.h"
#include "constraint/ContactPoint.h"
#include "utils/Profiler.h"
@ -43,14 +43,14 @@ const decimal ContactSolverSystem::BETA_SPLIT_IMPULSE = decimal(0.2);
const decimal ContactSolverSystem::SLOP = decimal(0.01);
// Constructor
ContactSolverSystem::ContactSolverSystem(MemoryManager& memoryManager, DynamicsWorld& world, Islands& islands, CollisionBodyComponents& bodyComponents,
RigidBodyComponents& rigidBodyComponents, ColliderComponents& colliderComponents,
const WorldSettings& worldSettings)
:mMemoryManager(memoryManager), mWorld(world), mContactConstraints(nullptr), mContactPoints(nullptr),
ContactSolverSystem::ContactSolverSystem(MemoryManager& memoryManager, PhysicsWorld& world, Islands& islands,
CollisionBodyComponents& bodyComponents, RigidBodyComponents& rigidBodyComponents,
ColliderComponents& colliderComponents, decimal& restitutionVelocityThreshold)
:mMemoryManager(memoryManager), mWorld(world), mRestitutionVelocityThreshold(restitutionVelocityThreshold),
mContactConstraints(nullptr), mContactPoints(nullptr),
mIslands(islands), mAllContactManifolds(nullptr), mAllContactPoints(nullptr),
mBodyComponents(bodyComponents), mRigidBodyComponents(rigidBodyComponents),
mColliderComponents(colliderComponents), mIsSplitImpulseActive(true),
mWorldSettings(worldSettings) {
mColliderComponents(colliderComponents), mIsSplitImpulseActive(true) {
#ifdef IS_PROFILING_ACTIVE
mProfiler = nullptr;
@ -237,7 +237,7 @@ void ContactSolverSystem::initializeForIsland(uint islandIndex) {
deltaV.y * mContactPoints[mNbContactPoints].normal.y +
deltaV.z * mContactPoints[mNbContactPoints].normal.z;
const decimal restitutionFactor = computeMixedRestitutionFactor(body1, body2);
if (deltaVDotN < -mWorldSettings.restitutionVelocityThreshold) {
if (deltaVDotN < -mRestitutionVelocityThreshold) {
mContactPoints[mNbContactPoints].restitutionBias = restitutionFactor * deltaVDotN;
}

View File

@ -30,7 +30,6 @@
#include "configuration.h"
#include "mathematics/Vector3.h"
#include "mathematics/Matrix3x3.h"
#include "engine/Islands.h"
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -42,7 +41,9 @@ class ContactManifold;
class MemoryManager;
class Profiler;
class Island;
struct Islands;
class RigidBody;
class PhysicsWorld;
class CollisionBodyComponents;
class DynamicsComponents;
class RigidBodyComponents;
@ -285,11 +286,14 @@ class ContactSolverSystem {
MemoryManager& mMemoryManager;
/// Physics world
DynamicsWorld& mWorld;
PhysicsWorld& mWorld;
/// Current time step
decimal mTimeStep;
/// Reference to the velocity threshold for contact velocity restitution
decimal& mRestitutionVelocityThreshold;
/// Contact constraints
// TODO : Use List<> here
ContactManifoldSolver* mContactConstraints;
@ -325,9 +329,6 @@ class ContactSolverSystem {
/// True if the split impulse position correction is active
bool mIsSplitImpulseActive;
/// World settings
const WorldSettings& mWorldSettings;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
@ -362,9 +363,8 @@ class ContactSolverSystem {
// -------------------- Methods -------------------- //
/// Constructor
ContactSolverSystem(MemoryManager& memoryManager, DynamicsWorld& world, Islands& islands, CollisionBodyComponents& bodyComponents,
RigidBodyComponents& rigidBodyComponents, ColliderComponents& colliderComponents,
const WorldSettings& worldSettings);
ContactSolverSystem(MemoryManager& memoryManager, PhysicsWorld& world, Islands& islands, CollisionBodyComponents& bodyComponents,
RigidBodyComponents& rigidBodyComponents, ColliderComponents& colliderComponents, decimal& restitutionVelocityThreshold);
/// Destructor
~ContactSolverSystem() = default;

View File

@ -26,12 +26,12 @@
// Libraries
#include "systems/DynamicsSystem.h"
#include "body/RigidBody.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
using namespace reactphysics3d;
// Constructor
DynamicsSystem::DynamicsSystem(DynamicsWorld& world, CollisionBodyComponents& collisionBodyComponents, RigidBodyComponents& rigidBodyComponents,
DynamicsSystem::DynamicsSystem(PhysicsWorld& world, CollisionBodyComponents& collisionBodyComponents, RigidBodyComponents& rigidBodyComponents,
TransformComponents& transformComponents, ColliderComponents& colliderComponents, bool& isGravityEnabled, Vector3& gravity)
:mWorld(world), mCollisionBodyComponents(collisionBodyComponents), mRigidBodyComponents(rigidBodyComponents), mTransformComponents(transformComponents), mColliderComponents(colliderComponents),
mIsGravityEnabled(isGravityEnabled), mGravity(gravity) {

View File

@ -35,7 +35,7 @@
namespace reactphysics3d {
class DynamicsWorld;
class PhysicsWorld;
// Class DynamicsSystem
/**
@ -49,7 +49,7 @@ class DynamicsSystem {
// -------------------- Attributes -------------------- //
/// Physics world
DynamicsWorld& mWorld;
PhysicsWorld& mWorld;
/// Reference to the collision body components
CollisionBodyComponents& mCollisionBodyComponents;
@ -80,7 +80,7 @@ class DynamicsSystem {
// -------------------- Methods -------------------- //
/// Constructor
DynamicsSystem(DynamicsWorld& world, CollisionBodyComponents& collisionBodyComponents,
DynamicsSystem(PhysicsWorld& world, CollisionBodyComponents& collisionBodyComponents,
RigidBodyComponents& rigidBodyComponents, TransformComponents& transformComponents,
ColliderComponents& colliderComponents, bool& isGravityEnabled, Vector3& gravity);

View File

@ -25,7 +25,7 @@
// Libraries
#include "systems/SolveBallAndSocketJointSystem.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
#include "body/RigidBody.h"
using namespace reactphysics3d;
@ -34,7 +34,7 @@ using namespace reactphysics3d;
const decimal SolveBallAndSocketJointSystem::BETA = decimal(0.2);
// Constructor
SolveBallAndSocketJointSystem::SolveBallAndSocketJointSystem(DynamicsWorld& world, RigidBodyComponents& rigidBodyComponents,
SolveBallAndSocketJointSystem::SolveBallAndSocketJointSystem(PhysicsWorld& world, RigidBodyComponents& rigidBodyComponents,
TransformComponents& transformComponents,
JointComponents& jointComponents,
BallAndSocketJointComponents& ballAndSocketJointComponents)

View File

@ -36,7 +36,7 @@
namespace reactphysics3d {
// Forward declarations
class DynamicsWorld;
class PhysicsWorld;
// Class SolveBallAndSocketJointSystem
/**
@ -54,7 +54,7 @@ class SolveBallAndSocketJointSystem {
// -------------------- Attributes -------------------- //
/// Physics world
DynamicsWorld& mWorld;
PhysicsWorld& mWorld;
/// Reference to the rigid body components
RigidBodyComponents& mRigidBodyComponents;
@ -85,7 +85,7 @@ class SolveBallAndSocketJointSystem {
// -------------------- Methods -------------------- //
/// Constructor
SolveBallAndSocketJointSystem(DynamicsWorld& world, RigidBodyComponents& rigidBodyComponents,
SolveBallAndSocketJointSystem(PhysicsWorld& world, RigidBodyComponents& rigidBodyComponents,
TransformComponents& transformComponents,
JointComponents& jointComponents,
BallAndSocketJointComponents& ballAndSocketJointComponents);

View File

@ -25,7 +25,7 @@
// Libraries
#include "systems/SolveFixedJointSystem.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
#include "body/RigidBody.h"
using namespace reactphysics3d;
@ -34,7 +34,7 @@ using namespace reactphysics3d;
const decimal SolveFixedJointSystem::BETA = decimal(0.2);
// Constructor
SolveFixedJointSystem::SolveFixedJointSystem(DynamicsWorld& world, RigidBodyComponents& rigidBodyComponents,
SolveFixedJointSystem::SolveFixedJointSystem(PhysicsWorld& world, RigidBodyComponents& rigidBodyComponents,
TransformComponents& transformComponents,
JointComponents& jointComponents,
FixedJointComponents& fixedJointComponents)

View File

@ -35,7 +35,7 @@
namespace reactphysics3d {
class DynamicsWorld;
class PhysicsWorld;
// Class SolveFixedJointSystem
/**
@ -53,7 +53,7 @@ class SolveFixedJointSystem {
// -------------------- Attributes -------------------- //
/// Physics world
DynamicsWorld& mWorld;
PhysicsWorld& mWorld;
/// Reference to the rigid body components
RigidBodyComponents& mRigidBodyComponents;
@ -84,7 +84,7 @@ class SolveFixedJointSystem {
// -------------------- Methods -------------------- //
/// Constructor
SolveFixedJointSystem(DynamicsWorld& world, RigidBodyComponents& rigidBodyComponents, TransformComponents& transformComponents,
SolveFixedJointSystem(PhysicsWorld& world, RigidBodyComponents& rigidBodyComponents, TransformComponents& transformComponents,
JointComponents& jointComponents, FixedJointComponents& fixedJointComponents);
/// Destructor

View File

@ -25,7 +25,7 @@
// Libraries
#include "systems/SolveHingeJointSystem.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
#include "body/RigidBody.h"
using namespace reactphysics3d;
@ -34,7 +34,7 @@ using namespace reactphysics3d;
const decimal SolveHingeJointSystem::BETA = decimal(0.2);
// Constructor
SolveHingeJointSystem::SolveHingeJointSystem(DynamicsWorld& world, RigidBodyComponents& rigidBodyComponents,
SolveHingeJointSystem::SolveHingeJointSystem(PhysicsWorld& world, RigidBodyComponents& rigidBodyComponents,
TransformComponents& transformComponents,
JointComponents& jointComponents,
HingeJointComponents& hingeJointComponents)

View File

@ -35,7 +35,7 @@
namespace reactphysics3d {
class DynamicsWorld;
class PhysicsWorld;
// Class SolveHingeJointSystem
/**
@ -53,7 +53,7 @@ class SolveHingeJointSystem {
// -------------------- Attributes -------------------- //
/// Physics world
DynamicsWorld& mWorld;
PhysicsWorld& mWorld;
/// Reference to the rigid body components
RigidBodyComponents& mRigidBodyComponents;
@ -100,7 +100,7 @@ class SolveHingeJointSystem {
// -------------------- Methods -------------------- //
/// Constructor
SolveHingeJointSystem(DynamicsWorld& world, RigidBodyComponents& rigidBodyComponents,
SolveHingeJointSystem(PhysicsWorld& world, RigidBodyComponents& rigidBodyComponents,
TransformComponents& transformComponents,
JointComponents& jointComponents,
HingeJointComponents& hingeJointComponents);

View File

@ -25,7 +25,7 @@
// Libraries
#include "systems/SolveSliderJointSystem.h"
#include "engine/DynamicsWorld.h"
#include "engine/PhysicsWorld.h"
#include "body/RigidBody.h"
using namespace reactphysics3d;
@ -34,7 +34,7 @@ using namespace reactphysics3d;
const decimal SolveSliderJointSystem::BETA = decimal(0.2);
// Constructor
SolveSliderJointSystem::SolveSliderJointSystem(DynamicsWorld& world, RigidBodyComponents& rigidBodyComponents,
SolveSliderJointSystem::SolveSliderJointSystem(PhysicsWorld& world, RigidBodyComponents& rigidBodyComponents,
TransformComponents& transformComponents,
JointComponents& jointComponents,
SliderJointComponents& sliderJointComponents)

View File

@ -35,7 +35,7 @@
namespace reactphysics3d {
class DynamicsWorld;
class PhysicsWorld;
// Class SolveSliderJointSystem
/**
@ -53,7 +53,7 @@ class SolveSliderJointSystem {
// -------------------- Attributes -------------------- //
/// Physics world
DynamicsWorld& mWorld;
PhysicsWorld& mWorld;
/// Reference to the rigid body components
RigidBodyComponents& mRigidBodyComponents;
@ -86,7 +86,7 @@ class SolveSliderJointSystem {
// -------------------- Methods -------------------- //
/// Constructor
SolveSliderJointSystem(DynamicsWorld& world, RigidBodyComponents& rigidBodyComponents,
SolveSliderJointSystem(PhysicsWorld& world, RigidBodyComponents& rigidBodyComponents,
TransformComponents& transformComponents,
JointComponents& jointComponents,
SliderJointComponents& sliderJointComponents);

View File

@ -268,7 +268,7 @@ class TestCollisionWorld : public Test {
PhysicsCommon mPhysicsCommon;
// Physics world
CollisionWorld* mWorld;
PhysicsWorld* mWorld;
// Bodies
CollisionBody* mBoxBody1;
@ -332,7 +332,7 @@ class TestCollisionWorld : public Test {
TestCollisionWorld(const std::string& name) : Test(name) {
// Create the collision world
mWorld = mPhysicsCommon.createCollisionWorld();
mWorld = mPhysicsCommon.createPhysicsWorld();
// ---------- Boxes ---------- //
Transform boxTransform1(Vector3(-20, 20, 0), Quaternion::identity());
@ -486,7 +486,7 @@ class TestCollisionWorld : public Test {
delete mConcaveMeshTriangleVertexArray;
mPhysicsCommon.destroyCollisionWorld(mWorld);
mPhysicsCommon.destroyPhysicsWorld(mWorld);
}
/// Run the tests

View File

@ -32,7 +32,7 @@
#include "collision/shapes/SphereShape.h"
#include "collision/shapes/CapsuleShape.h"
#include "collision/shapes/ConvexMeshShape.h"
#include "engine/CollisionWorld.h"
#include "engine/PhysicsWorld.h"
#include "engine/PhysicsCommon.h"
#include "collision/PolygonVertexArray.h"
@ -53,7 +53,7 @@ class TestPointInside : public Test {
PhysicsCommon mPhysicsCommon;
// Physics world
CollisionWorld* mWorld;
PhysicsWorld* mWorld;
// Bodies
CollisionBody* mBoxBody;
@ -97,7 +97,7 @@ class TestPointInside : public Test {
TestPointInside(const std::string& name) : Test(name) {
// Create the world
mWorld = mPhysicsCommon.createCollisionWorld();
mWorld = mPhysicsCommon.createPhysicsWorld();
// Body transform
Vector3 position(-3, 2, 7);
@ -180,7 +180,7 @@ class TestPointInside : public Test {
mPhysicsCommon.destroySphereShape(mSphereShape);
mPhysicsCommon.destroyCapsuleShape(mCapsuleShape);
mPhysicsCommon.destroyConvexMeshShape(mConvexMeshShape);
mPhysicsCommon.destroyCollisionWorld(mWorld);
mPhysicsCommon.destroyPhysicsWorld(mWorld);
mPhysicsCommon.destroyPolyhedronMesh(mConvexMeshPolyhedronMesh);
delete[] mConvexMeshPolygonFaces;
delete mConvexMeshPolygonVertexArray;

View File

@ -29,7 +29,7 @@
// Libraries
#include "Test.h"
#include "engine/PhysicsCommon.h"
#include "engine/CollisionWorld.h"
#include "engine/PhysicsWorld.h"
#include "body/CollisionBody.h"
#include "collision/shapes/BoxShape.h"
#include "collision/shapes/SphereShape.h"
@ -113,7 +113,7 @@ class TestRaycast : public Test {
decimal epsilon;
// Physics world
CollisionWorld* mWorld;
PhysicsWorld* mWorld;
// Bodies
CollisionBody* mBoxBody;
@ -172,7 +172,7 @@ class TestRaycast : public Test {
epsilon = decimal(0.0001);
// Create the world
mWorld = mPhysicsCommon.createCollisionWorld();
mWorld = mPhysicsCommon.createPhysicsWorld();
// Body transform
Vector3 position(-3, 2, 7);
@ -311,7 +311,7 @@ class TestRaycast : public Test {
mPhysicsCommon.destroyConcaveMeshShape(mConcaveMeshShape);
mPhysicsCommon.destroyHeightFieldShape(mHeightFieldShape);
mPhysicsCommon.destroyCollisionWorld(mWorld);
mPhysicsCommon.destroyPhysicsWorld(mWorld);
delete mConcaveMeshVertexArray;
delete mPolygonVertexArray;
@ -330,7 +330,7 @@ class TestRaycast : public Test {
}
/// Test the Collider::raycast(), CollisionBody::raycast() and
/// CollisionWorld::raycast() methods.
/// PhysicsWorld::raycast() methods.
void testBox() {
// ----- Test feedback data ----- //
@ -341,7 +341,7 @@ class TestRaycast : public Test {
mCallback.shapeToTest = mBoxCollider;
// CollisionWorld::raycast()
// PhysicsWorld::raycast()
mCallback.reset();
mWorld->raycast(ray, &mCallback);
rp3d_test(mCallback.isHit);
@ -542,7 +542,7 @@ class TestRaycast : public Test {
}
/// Test the Collider::raycast(), CollisionBody::raycast() and
/// CollisionWorld::raycast() methods.
/// PhysicsWorld::raycast() methods.
void testSphere() {
// ----- Test feedback data ----- //
@ -553,7 +553,7 @@ class TestRaycast : public Test {
mCallback.shapeToTest = mSphereCollider;
// CollisionWorld::raycast()
// PhysicsWorld::raycast()
mCallback.reset();
mWorld->raycast(ray, &mCallback);
rp3d_test(mCallback.isHit);
@ -752,7 +752,7 @@ class TestRaycast : public Test {
}
/// Test the Collider::raycast(), CollisionBody::raycast() and
/// CollisionWorld::raycast() methods.
/// PhysicsWorld::raycast() methods.
void testCapsule() {
// ----- Test feedback data ----- //
@ -773,7 +773,7 @@ class TestRaycast : public Test {
mCallback.shapeToTest = mCapsuleCollider;
// CollisionWorld::raycast()
// PhysicsWorld::raycast()
mCallback.reset();
mWorld->raycast(ray, &mCallback);
rp3d_test(mCallback.isHit);
@ -992,7 +992,7 @@ class TestRaycast : public Test {
}
/// Test the Collider::raycast(), CollisionBody::raycast() and
/// CollisionWorld::raycast() methods.
/// PhysicsWorld::raycast() methods.
void testConvexMesh() {
// ----- Test feedback data ----- //
@ -1003,7 +1003,7 @@ class TestRaycast : public Test {
mCallback.shapeToTest = mConvexMeshCollider;
// CollisionWorld::raycast()
// PhysicsWorld::raycast()
mCallback.reset();
mWorld->raycast(ray, &mCallback);
rp3d_test(mCallback.isHit);
@ -1205,7 +1205,7 @@ class TestRaycast : public Test {
}
/// Test the CollisionBody::raycast() and
/// CollisionWorld::raycast() methods.
/// PhysicsWorld::raycast() methods.
void testCompound() {
// ----- Test feedback data ----- //
@ -1349,7 +1349,7 @@ class TestRaycast : public Test {
mCallback.shapeToTest = mConcaveMeshCollider;
// CollisionWorld::raycast()
// PhysicsWorld::raycast()
mCallback.reset();
mWorld->raycast(ray, &mCallback);
rp3d_test(mCallback.isHit);
@ -1584,7 +1584,7 @@ class TestRaycast : public Test {
mCallback.shapeToTest = mHeightFieldCollider;
// CollisionWorld::raycast()
// PhysicsWorld::raycast()
mCallback.reset();
mWorld->raycast(ray, &mCallback);
rp3d_test(mCallback.isHit);

View File

@ -38,7 +38,7 @@ openglframework::VertexArrayObject Box::mVAO;
int Box::totalNbBoxes = 0;
// Constructor
Box::Box(const openglframework::Vector3& size, reactphysics3d::PhysicsCommon& physicsCommon, reactphysics3d::CollisionWorld* world,
Box::Box(const openglframework::Vector3& size, reactphysics3d::PhysicsCommon& physicsCommon, reactphysics3d::PhysicsWorld* world,
const std::string& meshFolderPath)
: PhysicsObject(physicsCommon, meshFolderPath + "cube.obj") {
@ -61,7 +61,7 @@ Box::Box(const openglframework::Vector3& size, reactphysics3d::PhysicsCommon& ph
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body in the dynamics world
// Create a rigid body in the physics world
mBody = world->createCollisionBody(mPreviousTransform);
// Add the collision shape to the body
@ -80,7 +80,7 @@ Box::Box(const openglframework::Vector3& size, reactphysics3d::PhysicsCommon& ph
}
// Constructor
Box::Box(const openglframework::Vector3& size, float mass, reactphysics3d::PhysicsCommon &physicsCommon, reactphysics3d::DynamicsWorld* world,
Box::Box(const openglframework::Vector3& size, float mass, reactphysics3d::PhysicsCommon &physicsCommon, reactphysics3d::PhysicsWorld* world,
const std::string& meshFolderPath)
: PhysicsObject(physicsCommon, meshFolderPath + "cube.obj") {
@ -102,7 +102,7 @@ Box::Box(const openglframework::Vector3& size, float mass, reactphysics3d::Physi
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body in the dynamics world
// Create a rigid body in the physics world
rp3d::RigidBody* body = world->createRigidBody(mPreviousTransform);
// Add the collision shape to the body

View File

@ -76,10 +76,10 @@ class Box : public PhysicsObject {
/// Constructor
Box(const openglframework::Vector3& size, reactphysics3d::PhysicsCommon& physicsCommon,
reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath);
reactphysics3d::PhysicsWorld* world, const std::string& meshFolderPath);
/// Constructor
Box(const openglframework::Vector3& size, float mass, reactphysics3d::PhysicsCommon& physicsCommon, reactphysics3d::DynamicsWorld *world, const std::string& meshFolderPath);
Box(const openglframework::Vector3& size, float mass, reactphysics3d::PhysicsCommon& physicsCommon, reactphysics3d::PhysicsWorld *world, const std::string& meshFolderPath);
/// Destructor
~Box();

View File

@ -34,41 +34,7 @@ openglframework::VertexArrayObject Capsule::mVAO;
int Capsule::totalNbCapsules = 0;
// Constructor
Capsule::Capsule(float radius, float height, rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld* world, const std::string& meshFolderPath)
: PhysicsObject(physicsCommon, meshFolderPath + "capsule.obj"), mRadius(radius), mHeight(height) {
// Compute the scaling matrix
mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0,
0, (mHeight + 2.0f * mRadius) / 3, 0,0,
0, 0, mRadius, 0,
0, 0, 0, 1.0f);
// Create the collision shape for the rigid body (sphere shape)
// ReactPhysics3D will clone this object to create an internal one. Therefore,
// it is OK if this object is destroyed right after calling RigidBody::addCollisionShape()
mCapsuleShape = mPhysicsCommon.createCapsuleShape(mRadius, mHeight);
//mCapsuleShape->setLocalScaling(rp3d::Vector3(2, 2, 2));
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body corresponding in the dynamics world
mBody = world->createCollisionBody(mPreviousTransform);
// Add a collision shape to the body and specify the mass of the shape
mCollider = mBody->addCollider(mCapsuleShape, rp3d::Transform::identity());
mTransformMatrix = mTransformMatrix * mScalingMatrix;
// Create the VBOs and VAO
if (totalNbCapsules == 0) {
createVBOAndVAO();
}
totalNbCapsules++;
}
// Constructor
Capsule::Capsule(float radius, float height, float mass, reactphysics3d::PhysicsCommon &physicsCommon, rp3d::DynamicsWorld* dynamicsWorld,
Capsule::Capsule(bool createRigidBody, float radius, float height, float mass, reactphysics3d::PhysicsCommon &physicsCommon, rp3d::PhysicsWorld* physicsWorld,
const std::string& meshFolderPath)
: PhysicsObject(physicsCommon, meshFolderPath + "capsule.obj"), mRadius(radius), mHeight(height) {
@ -85,13 +51,24 @@ Capsule::Capsule(float radius, float height, float mass, reactphysics3d::Physics
// it is OK if this object is destroyed right after calling RigidBody::addCollisionShape()
mCapsuleShape = mPhysicsCommon.createCapsuleShape(mRadius, mHeight);
// Create a rigid body corresponding in the dynamics world
rp3d::RigidBody* body = dynamicsWorld->createRigidBody(mPreviousTransform);
// Create a body corresponding in the physics world
if (createRigidBody) {
// Add a collision shape to the body and specify the mass of the shape
mCollider = body->addCollider(mCapsuleShape, rp3d::Transform::identity(), mass);
rp3d::RigidBody* body = physicsWorld->createRigidBody(mPreviousTransform);
mBody = body;
// Add a collision shape to the body and specify the mass of the shape
mCollider = body->addCollider(mCapsuleShape, rp3d::Transform::identity(), mass);
mBody = body;
}
else {
// Create a rigid body corresponding in the physics world
mBody = physicsWorld->createCollisionBody(mPreviousTransform);
// Add a collision shape to the body and specify the mass of the shape
mCollider = mBody->addCollider(mCapsuleShape, rp3d::Transform::identity());
}
mTransformMatrix = mTransformMatrix * mScalingMatrix;

View File

@ -82,11 +82,8 @@ class Capsule : public PhysicsObject {
// -------------------- Methods -------------------- //
/// Constructor
Capsule(float radius, float height, reactphysics3d::PhysicsCommon &physicsCommon, rp3d::CollisionWorld* world, const std::string& meshFolderPath);
/// Constructor
Capsule(float radius, float height, float mass, reactphysics3d::PhysicsCommon& physicsCommon, rp3d::DynamicsWorld* dynamicsWorld,
const std::string& meshFolderPath);
Capsule(bool createRigidBody, float radius, float height, float mass, reactphysics3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* physicsWorld,
const std::string& meshFolderPath);
/// Destructor
~Capsule();

View File

@ -27,7 +27,7 @@
#include "ConcaveMesh.h"
// Constructor
ConcaveMesh::ConcaveMesh(rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld* world, const std::string& meshPath)
ConcaveMesh::ConcaveMesh(rp3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* world, const std::string& meshPath)
: PhysicsObject(physicsCommon, meshPath), mVBOVertices(GL_ARRAY_BUFFER),
mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER),
mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) {
@ -59,7 +59,7 @@ ConcaveMesh::ConcaveMesh(rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorl
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body corresponding to the sphere in the dynamics world
// Create a rigid body corresponding to the sphere in the physics world
mBody = world->createCollisionBody(mPreviousTransform);
// Add a collision shape to the body and specify the mass of the collision shape
@ -72,7 +72,7 @@ ConcaveMesh::ConcaveMesh(rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorl
}
// Constructor
ConcaveMesh::ConcaveMesh(float mass, reactphysics3d::PhysicsCommon& physicsCommon, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath)
ConcaveMesh::ConcaveMesh(float mass, reactphysics3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* physicsWorld, const std::string& meshPath)
: PhysicsObject(physicsCommon, meshPath), mVBOVertices(GL_ARRAY_BUFFER),
mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER),
mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) {
@ -102,8 +102,8 @@ ConcaveMesh::ConcaveMesh(float mass, reactphysics3d::PhysicsCommon& physicsCommo
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body corresponding to the sphere in the dynamics world
rp3d::RigidBody* body = dynamicsWorld->createRigidBody(mPreviousTransform);
// Create a rigid body corresponding to the sphere in the physics world
rp3d::RigidBody* body = physicsWorld->createRigidBody(mPreviousTransform);
// Add a collision shape to the body and specify the mass of the collision shape
mCollider = body->addCollider(mConcaveShape, rp3d::Transform::identity(), mass);

View File

@ -76,10 +76,10 @@ class ConcaveMesh : public PhysicsObject {
// -------------------- Methods -------------------- //
/// Constructor
ConcaveMesh(reactphysics3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld* world, const std::string& meshPath);
ConcaveMesh(reactphysics3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* world, const std::string& meshPath);
/// Constructor
ConcaveMesh(float mass, reactphysics3d::PhysicsCommon& physicsCommon, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath);
ConcaveMesh(float mass, reactphysics3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* physicsWorld, const std::string& meshPath);
/// Destructor
~ConcaveMesh();

View File

@ -28,7 +28,7 @@
#include <unordered_set>
// Constructor
ConvexMesh::ConvexMesh(rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld* world, const std::string& meshPath)
ConvexMesh::ConvexMesh(rp3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* world, const std::string& meshPath)
: PhysicsObject(physicsCommon, meshPath), mVBOVertices(GL_ARRAY_BUFFER),
mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER),
mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) {
@ -75,7 +75,7 @@ ConvexMesh::ConvexMesh(rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld*
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body corresponding to the sphere in the dynamics world
// Create a rigid body corresponding to the sphere in the physics world
mBody = world->createCollisionBody(mPreviousTransform);
// Add a collision shape to the body and specify the mass of the collision shape
@ -88,7 +88,7 @@ ConvexMesh::ConvexMesh(rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld*
}
// Constructor
ConvexMesh::ConvexMesh(float mass, rp3d::PhysicsCommon& physicsCommon, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath)
ConvexMesh::ConvexMesh(float mass, rp3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* physicsWorld, const std::string& meshPath)
: PhysicsObject(physicsCommon, meshPath), mVBOVertices(GL_ARRAY_BUFFER),
mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER),
mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) {
@ -135,8 +135,8 @@ ConvexMesh::ConvexMesh(float mass, rp3d::PhysicsCommon& physicsCommon, rp3d::Dyn
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body corresponding to the sphere in the dynamics world
rp3d::RigidBody* body = dynamicsWorld->createRigidBody(mPreviousTransform);
// Create a rigid body corresponding to the sphere in the physics world
rp3d::RigidBody* body = physicsWorld->createRigidBody(mPreviousTransform);
// Add a collision shape to the body and specify the mass of the collision shape
mCollider = body->addCollider(mConvexShape, rp3d::Transform::identity(), mass);

View File

@ -89,10 +89,10 @@ class ConvexMesh : public PhysicsObject {
// -------------------- Methods -------------------- //
/// Constructor
ConvexMesh(rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld* world, const std::string& meshPath);
ConvexMesh(rp3d::PhysicsCommon& physicsCommon, reactphysics3d::PhysicsWorld* world, const std::string& meshPath);
/// Constructor
ConvexMesh(float mass, rp3d::PhysicsCommon& physicsCommon, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath);
ConvexMesh(float mass, rp3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* physicsWorld, const std::string& meshPath);
/// Destructor
~ConvexMesh();

View File

@ -34,7 +34,7 @@ openglframework::VertexArrayObject Dumbbell::mVAO;
int Dumbbell::totalNbDumbbells = 0;
// Constructor
Dumbbell::Dumbbell(rp3d::PhysicsCommon& physicsCommon, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath)
Dumbbell::Dumbbell(bool createRigidBody, rp3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* physicsWorld, const std::string& meshFolderPath)
: PhysicsObject(physicsCommon, meshFolderPath + "dumbbell.obj") {
// Identity scaling matrix
@ -68,66 +68,28 @@ Dumbbell::Dumbbell(rp3d::PhysicsCommon& physicsCommon, rp3d::DynamicsWorld* dyna
// Initial transform of the cylinder collision shape of the dumbell (in local-space)
rp3d::Transform transformCylinderShape(rp3d::Vector3(0, 0, 0), rp3d::Quaternion::identity());
// Create a rigid body corresponding to the dumbbell in the dynamics world
rp3d::RigidBody* body = dynamicsWorld->createRigidBody(mPreviousTransform);
// Create a body corresponding to the dumbbell in the physics world
if (createRigidBody) {
// Add the three collision shapes to the body and specify the mass and transform of the shapes
mColliderSphere1 = body->addCollider(mSphereShape, transformSphereShape1, massSphere);
mColliderSphere2 = body->addCollider(mSphereShape, transformSphereShape2, massSphere);
mColliderCapsule = body->addCollider(mCapsuleShape, transformCylinderShape, massCylinder);
rp3d::RigidBody* body;
body = physicsWorld->createRigidBody(mPreviousTransform);
mBody = body;
// Add the three collision shapes to the body and specify the mass and transform of the shapes
mColliderSphere1 = body->addCollider(mSphereShape, transformSphereShape1, massSphere);
mColliderSphere2 = body->addCollider(mSphereShape, transformSphereShape2, massSphere);
mColliderCapsule = body->addCollider(mCapsuleShape, transformCylinderShape, massCylinder);
mTransformMatrix = mTransformMatrix * mScalingMatrix;
// Create the VBOs and VAO
if (totalNbDumbbells == 0) {
createVBOAndVAO();
mBody = body;
}
else {
totalNbDumbbells++;
}
mBody = physicsWorld->createCollisionBody(mPreviousTransform);
// Constructor
Dumbbell::Dumbbell(reactphysics3d::PhysicsCommon &physicsCommon, rp3d::CollisionWorld* world, const std::string& meshFolderPath)
: PhysicsObject(physicsCommon, meshFolderPath + "dumbbell.obj"){
// Identity scaling matrix
mScalingMatrix.setToIdentity();
mDistanceBetweenSphere = 8.0f;
// Create a sphere collision shape for the two ends of the dumbbell
// ReactPhysics3D will clone this object to create an internal one. Therefore,
// it is OK if this object is destroyed right after calling RigidBody::addCollisionShape()
const rp3d::decimal radiusSphere = rp3d::decimal(1.5);
mSphereShape = mPhysicsCommon.createSphereShape(radiusSphere);
// Create a cylinder collision shape for the middle of the dumbbell
// ReactPhysics3D will clone this object to create an internal one. Therefore,
// it is OK if this object is destroyed right after calling RigidBody::addCollisionShape()
const rp3d::decimal radiusCapsule = rp3d::decimal(0.5);
const rp3d::decimal heightCapsule = rp3d::decimal(7.0);
mCapsuleShape = mPhysicsCommon.createCapsuleShape(radiusCapsule, heightCapsule);
// Initial transform of the first sphere collision shape of the dumbbell (in local-space)
rp3d::Transform transformSphereShape1(rp3d::Vector3(0, mDistanceBetweenSphere / 2.0f, 0), rp3d::Quaternion::identity());
// Initial transform of the second sphere collision shape of the dumbell (in local-space)
rp3d::Transform transformSphereShape2(rp3d::Vector3(0, -mDistanceBetweenSphere / 2.0f, 0), rp3d::Quaternion::identity());
// Initial transform of the cylinder collision shape of the dumbell (in local-space)
rp3d::Transform transformCylinderShape(rp3d::Vector3(0, 0, 0), rp3d::Quaternion::identity());
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body corresponding to the dumbbell in the dynamics world
mBody = world->createCollisionBody(mPreviousTransform);
// Add the three collision shapes to the body and specify the mass and transform of the shapes
mColliderSphere1 = mBody->addCollider(mSphereShape, transformSphereShape1);
mColliderSphere2 = mBody->addCollider(mSphereShape, transformSphereShape2);
mColliderCapsule = mBody->addCollider(mCapsuleShape, transformCylinderShape);
// Add the three collision shapes to the body and specify the mass and transform of the shapes
mColliderSphere1 = mBody->addCollider(mSphereShape, transformSphereShape1);
mColliderSphere2 = mBody->addCollider(mSphereShape, transformSphereShape2);
mColliderCapsule = mBody->addCollider(mCapsuleShape, transformCylinderShape);
}
mTransformMatrix = mTransformMatrix * mScalingMatrix;

View File

@ -82,10 +82,8 @@ class Dumbbell : public PhysicsObject {
// -------------------- Methods -------------------- //
/// Constructor
Dumbbell(reactphysics3d::PhysicsCommon& physicsCommon, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath);
/// Constructor
Dumbbell(reactphysics3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld* world, const std::string& meshFolderPath);
Dumbbell(bool createRigidBody, reactphysics3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* physicsWorld,
const std::string& meshFolderPath);
/// Destructor
~Dumbbell();

View File

@ -28,7 +28,7 @@
#include "PerlinNoise.h"
// Constructor
HeightField::HeightField(rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld* world)
HeightField::HeightField(rp3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* world)
: PhysicsObject(physicsCommon), mVBOVertices(GL_ARRAY_BUFFER),
mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER),
mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) {
@ -49,7 +49,7 @@ HeightField::HeightField(rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorl
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body corresponding to the sphere in the dynamics world
// Create a rigid body corresponding to the sphere in the physics world
mBody = world->createCollisionBody(mPreviousTransform);
// Add a collision shape to the body and specify the mass of the collision shape
@ -62,7 +62,7 @@ HeightField::HeightField(rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorl
}
// Constructor
HeightField::HeightField(float mass, reactphysics3d::PhysicsCommon& physicsCommon, rp3d::DynamicsWorld* dynamicsWorld)
HeightField::HeightField(float mass, reactphysics3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* physicsWorld)
: PhysicsObject(physicsCommon), mVBOVertices(GL_ARRAY_BUFFER),
mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER),
mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) {
@ -83,8 +83,8 @@ HeightField::HeightField(float mass, reactphysics3d::PhysicsCommon& physicsCommo
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body corresponding to the sphere in the dynamics world
rp3d::RigidBody* body = dynamicsWorld->createRigidBody(mPreviousTransform);
// Create a rigid body corresponding to the sphere in the physics world
rp3d::RigidBody* body = physicsWorld->createRigidBody(mPreviousTransform);
// Add a collision shape to the body and specify the mass of the collision shape
mCollider = body->addCollider(mHeightFieldShape, rp3d::Transform::identity(), mass);

View File

@ -89,10 +89,10 @@ class HeightField : public PhysicsObject {
// -------------------- Methods -------------------- //
/// Constructor
HeightField(reactphysics3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld* world);
HeightField(reactphysics3d::PhysicsCommon& physicsCommon, reactphysics3d::PhysicsWorld* world);
/// Constructor
HeightField(float mass, rp3d::PhysicsCommon& physicsCommon, rp3d::DynamicsWorld* dynamicsWorld);
HeightField(float mass, rp3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* physicsWorld);
/// Destructor
~HeightField();

View File

@ -34,7 +34,7 @@ openglframework::VertexArrayObject Sphere::mVAO;
int Sphere::totalNbSpheres = 0;
// Constructor
Sphere::Sphere(float radius, rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld* world,
Sphere::Sphere(float radius, rp3d::PhysicsCommon& physicsCommon, rp3d::PhysicsWorld* world,
const std::string& meshFolderPath)
: PhysicsObject(physicsCommon, meshFolderPath + "sphere.obj"), mRadius(radius) {
@ -52,7 +52,7 @@ Sphere::Sphere(float radius, rp3d::PhysicsCommon& physicsCommon, rp3d::Collision
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body corresponding to the sphere in the dynamics world
// Create a rigid body corresponding to the sphere in the physics world
mBody = world->createCollisionBody(mPreviousTransform);
// Add a collision shape to the body and specify the mass of the shape
@ -69,7 +69,7 @@ Sphere::Sphere(float radius, rp3d::PhysicsCommon& physicsCommon, rp3d::Collision
}
// Constructor
Sphere::Sphere(float radius, float mass, rp3d::PhysicsCommon& physicsCommon,reactphysics3d::DynamicsWorld* world,
Sphere::Sphere(float radius, float mass, rp3d::PhysicsCommon& physicsCommon,reactphysics3d::PhysicsWorld* world,
const std::string& meshFolderPath)
: PhysicsObject(physicsCommon, meshFolderPath + "sphere.obj"), mRadius(radius) {
@ -86,7 +86,7 @@ Sphere::Sphere(float radius, float mass, rp3d::PhysicsCommon& physicsCommon,rea
mPreviousTransform = rp3d::Transform::identity();
// Create a rigid body corresponding to the sphere in the dynamics world
// Create a rigid body corresponding to the sphere in the physics world
rp3d::RigidBody* body = world->createRigidBody(mPreviousTransform);
// Add a collision shape to the body and specify the mass of the shape

View File

@ -79,13 +79,13 @@ class Sphere : public PhysicsObject {
// -------------------- Methods -------------------- //
/// Constructor
Sphere(float radius, rp3d::PhysicsCommon& physicsCommon, rp3d::CollisionWorld* world, const std::string& meshFolderPath);
Sphere(float radius, rp3d::PhysicsCommon& physicsCommon, reactphysics3d::PhysicsWorld* world, const std::string& meshFolderPath);
/// Constructor
Sphere(float radius, float mass, reactphysics3d::PhysicsCommon &physicsCommon, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath);
Sphere(float radius, float mass, reactphysics3d::PhysicsCommon &physicsCommon, rp3d::PhysicsWorld* physicsWorld, const std::string& meshFolderPath);
/// Destructor
~Sphere();
virtual ~Sphere() override;
/// Render the sphere at the correct position and with the correct orientation
void virtual render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) override;

View File

@ -48,15 +48,15 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// Set the center of the scene
setScenePosition(center, SCENE_RADIUS);
rp3d::WorldSettings worldSettings;
rp3d::PhysicsWorld::WorldSettings worldSettings;
worldSettings.worldName = name;
// Create the dynamics world for the physics simulation
mPhysicsWorld = mPhysicsCommon.createCollisionWorld(worldSettings);
// Create the physics world for the physics simulation
mPhysicsWorld = mPhysicsCommon.createPhysicsWorld(worldSettings);
// ---------- Sphere 1 ---------- //
// Create a sphere and a corresponding collision body in the dynamics world
// Create a sphere and a corresponding collision body in the physics world
mSphere1 = new Sphere(4, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mAllShapes.push_back(mSphere1);
@ -68,7 +68,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// ---------- Sphere 2 ---------- //
// Create a sphere and a corresponding collision body in the dynamics world
// Create a sphere and a corresponding collision body in the physics world
mSphere2 = new Sphere(2, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mAllShapes.push_back(mSphere2);
@ -80,8 +80,8 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// ---------- Capsule 1 ---------- //
// Create a cylinder and a corresponding collision body in the dynamics world
mCapsule1 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Create a cylinder and a corresponding collision body in the physics world
mCapsule1 = new Capsule(false, CAPSULE_RADIUS, CAPSULE_HEIGHT, 1.0, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mAllShapes.push_back(mCapsule1);
// Set the color
@ -91,8 +91,8 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// ---------- Capsule 2 ---------- //
// Create a cylinder and a corresponding collision body in the dynamics world
mCapsule2 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Create a cylinder and a corresponding collision body in the physics world
mCapsule2 = new Capsule(false, CAPSULE_RADIUS, CAPSULE_HEIGHT, 1.0, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mAllShapes.push_back(mCapsule2);
// Set the color
@ -102,7 +102,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// ---------- Concave Mesh ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world
// Create a convex mesh and a corresponding collision body in the physics world
mConcaveMesh = new ConcaveMesh(mPhysicsCommon, mPhysicsWorld, mMeshFolderPath + "city.obj");
mAllShapes.push_back(mConcaveMesh);
@ -113,7 +113,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// ---------- Box 1 ---------- //
// Create a cylinder and a corresponding collision body in the dynamics world
// Create a cylinder and a corresponding collision body in the physics world
mBox1 = new Box(BOX_SIZE, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mAllShapes.push_back(mBox1);
@ -124,7 +124,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// ---------- Box 2 ---------- //
// Create a cylinder and a corresponding collision body in the dynamics world
// Create a cylinder and a corresponding collision body in the physics world
mBox2 = new Box(openglframework::Vector3(3, 2, 5), mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mAllShapes.push_back(mBox2);
@ -135,7 +135,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// ---------- Convex Mesh ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world
// Create a convex mesh and a corresponding collision body in the physics world
mConvexMesh = new ConvexMesh(mPhysicsCommon, mPhysicsWorld, mMeshFolderPath + "convexmesh.obj");
mAllShapes.push_back(mConvexMesh);
@ -146,7 +146,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// ---------- Heightfield ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world
// Create a convex mesh and a corresponding collision body in the physics world
mHeightField = new HeightField(mPhysicsCommon, mPhysicsWorld);
// Set the color
@ -176,7 +176,7 @@ void CollisionDetectionScene::reset() {
// Destructor
CollisionDetectionScene::~CollisionDetectionScene() {
// Destroy the box rigid body from the dynamics world
// Destroy the box rigid body from the physics world
//mPhysicsWorld->destroyCollisionBody(mBox->getCollisionBody());
//delete mBox;
@ -211,8 +211,8 @@ CollisionDetectionScene::~CollisionDetectionScene() {
// Destroy the static data for the visual contact points
VisualContactPoint::destroyStaticData();
// Destroy the collision world
mPhysicsCommon.destroyCollisionWorld(mPhysicsWorld);
// Destroy the physics world
mPhysicsCommon.destroyPhysicsWorld(mPhysicsWorld);
}
// Take a step for the simulation

View File

@ -32,7 +32,7 @@ using namespace collisionshapesscene;
// Constructor
CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettings& settings)
: SceneDemo(name, settings, SCENE_RADIUS) {
: SceneDemo(name, settings, true, SCENE_RADIUS) {
std::string meshFolderPath("meshes/");
@ -42,21 +42,21 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin
// Set the center of the scene
setScenePosition(center, SCENE_RADIUS);
// Gravity vector in the dynamics world
// Gravity vector in the physics world
rp3d::Vector3 gravity(0, -9.81f, 0);
rp3d::WorldSettings worldSettings;
rp3d::PhysicsWorld::WorldSettings worldSettings;
worldSettings.worldName = name;
// Create the dynamics world for the physics simulation
rp3d::DynamicsWorld* dynamicsWorld = mPhysicsCommon.createDynamicsWorld(gravity, worldSettings);
dynamicsWorld->setEventListener(this);
mPhysicsWorld = dynamicsWorld;
// Create the physics world for the physics simulation
rp3d::PhysicsWorld* physicsWorld = mPhysicsCommon.createPhysicsWorld(worldSettings);
physicsWorld->setEventListener(this);
mPhysicsWorld = physicsWorld;
for (int i=0; i<NB_COMPOUND_SHAPES; i++) {
// Create a convex mesh and a corresponding rigid in the dynamics world
Dumbbell* dumbbell = new Dumbbell(mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a convex mesh and a corresponding rigid in the physics world
Dumbbell* dumbbell = new Dumbbell(true, mPhysicsCommon, mPhysicsWorld, meshFolderPath);
// Set the box color
dumbbell->setColor(mObjectColorDemo);
@ -74,8 +74,8 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin
// Create all the boxes of the scene
for (int i=0; i<NB_BOXES; i++) {
// Create a sphere and a corresponding rigid in the dynamics world
Box* box = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
// Create a sphere and a corresponding rigid in the physics world
Box* box = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Set the box color
box->setColor(mObjectColorDemo);
@ -93,8 +93,8 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin
// Create all the spheres of the scene
for (int i=0; i<NB_SPHERES; i++) {
// Create a sphere and a corresponding rigid in the dynamics world
Sphere* sphere = new Sphere(SPHERE_RADIUS, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a sphere and a corresponding rigid in the physics world
Sphere* sphere = new Sphere(SPHERE_RADIUS, BOX_MASS, mPhysicsCommon, mPhysicsWorld, meshFolderPath);
// Add some rolling resistance
sphere->getRigidBody()->getMaterial().setRollingResistance(rp3d::decimal(0.08));
@ -115,9 +115,9 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin
// Create all the capsules of the scene
for (int i=0; i<NB_CAPSULES; i++) {
// Create a cylinder and a corresponding rigid in the dynamics world
Capsule* capsule = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, CAPSULE_MASS,
mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a cylinder and a corresponding rigid in the physics world
Capsule* capsule = new Capsule(true, CAPSULE_RADIUS, CAPSULE_HEIGHT, CAPSULE_MASS,
mPhysicsCommon, mPhysicsWorld, meshFolderPath);
capsule->getRigidBody()->getMaterial().setRollingResistance(rp3d::decimal(0.08f));
@ -137,8 +137,8 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin
// Create all the convex meshes of the scene
for (int i=0; i<NB_MESHES; i++) {
// Create a convex mesh and a corresponding rigid in the dynamics world
ConvexMesh* mesh = new ConvexMesh(MESH_MASS, mPhysicsCommon, getDynamicsWorld(), meshFolderPath + "convexmesh.obj");
// Create a convex mesh and a corresponding rigid in the physics world
ConvexMesh* mesh = new ConvexMesh(MESH_MASS, mPhysicsCommon, mPhysicsWorld, meshFolderPath + "convexmesh.obj");
// Set the box color
mesh->setColor(mObjectColorDemo);
@ -155,7 +155,7 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin
// ---------- Create the floor ---------
mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mPhysicsObjects.push_back(mFloor);
// Set the box color
@ -170,15 +170,15 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin
material.setBounciness(rp3d::decimal(0.2));
// Get the physics engine parameters
mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled();
rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity();
mEngineSettings.isGravityEnabled = mPhysicsWorld->isGravityEnabled();
rp3d::Vector3 gravityVector = mPhysicsWorld->getGravity();
mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z);
mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep();
mEngineSettings.isSleepingEnabled = mPhysicsWorld->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = mPhysicsWorld->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = mPhysicsWorld->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = mPhysicsWorld->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = mPhysicsWorld->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = mPhysicsWorld->getTimeBeforeSleep();
}
// Destructor
@ -187,15 +187,15 @@ CollisionShapesScene::~CollisionShapesScene() {
// Destroy all the physics objects of the scene
for (std::vector<PhysicsObject*>::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) {
// Destroy the corresponding rigid body from the dynamics world
getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody());
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyRigidBody((*it)->getRigidBody());
// Destroy the object
delete (*it);
}
// Destroy the dynamics world
mPhysicsCommon.destroyDynamicsWorld(static_cast<rp3d::DynamicsWorld*>(mPhysicsWorld));
// Destroy the physics world
mPhysicsCommon.destroyPhysicsWorld(static_cast<rp3d::PhysicsWorld*>(mPhysicsWorld));
}
/// Reset the scene

View File

@ -32,7 +32,7 @@ using namespace trianglemeshscene;
// Constructor
ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& settings)
: SceneDemo(name, settings, SCENE_RADIUS) {
: SceneDemo(name, settings, true, SCENE_RADIUS) {
std::string meshFolderPath("meshes/");
@ -42,22 +42,22 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& sett
// Set the center of the scene
setScenePosition(center, SCENE_RADIUS);
// Gravity vector in the dynamics world
// Gravity vector in the physics world
rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0);
rp3d::WorldSettings worldSettings;
rp3d::PhysicsWorld::WorldSettings worldSettings;
worldSettings.worldName = name;
// Create the dynamics world for the physics simulation
rp3d::DynamicsWorld* dynamicsWorld = mPhysicsCommon.createDynamicsWorld(gravity, worldSettings);
dynamicsWorld->setEventListener(this);
mPhysicsWorld = dynamicsWorld;
// Create the physics world for the physics simulation
rp3d::PhysicsWorld* physicsWorld = mPhysicsCommon.createPhysicsWorld(worldSettings);
physicsWorld->setEventListener(this);
mPhysicsWorld = physicsWorld;
// ---------- Create the boxes ----------- //
for (int i = 0; i<NB_COMPOUND_SHAPES; i++) {
// Create a convex mesh and a corresponding rigid in the dynamics world
Dumbbell* dumbbell = new Dumbbell(mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a convex mesh and a corresponding rigid in the physics world
Dumbbell* dumbbell = new Dumbbell(true, mPhysicsCommon, mPhysicsWorld, meshFolderPath);
// Set the box color
dumbbell->setColor(mObjectColorDemo);
@ -75,8 +75,8 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& sett
// Create all the boxes of the scene
for (int i = 0; i<NB_BOXES; i++) {
// Create a sphere and a corresponding rigid in the dynamics world
Box* box = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
// Create a sphere and a corresponding rigid in the physics world
Box* box = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Set the box color
box->setColor(mObjectColorDemo);
@ -94,8 +94,8 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& sett
// Create all the spheres of the scene
for (int i = 0; i<NB_SPHERES; i++) {
// Create a sphere and a corresponding rigid in the dynamics world
Sphere* sphere = new Sphere(SPHERE_RADIUS, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a sphere and a corresponding rigid in the physics world
Sphere* sphere = new Sphere(SPHERE_RADIUS, BOX_MASS, mPhysicsCommon, mPhysicsWorld, meshFolderPath);
// Add some rolling resistance
sphere->getRigidBody()->getMaterial().setRollingResistance(rp3d::decimal(0.08));
@ -116,9 +116,9 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& sett
// Create all the capsules of the scene
for (int i = 0; i<NB_CAPSULES; i++) {
// Create a cylinder and a corresponding rigid in the dynamics world
Capsule* capsule = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, CAPSULE_MASS,
mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a cylinder and a corresponding rigid in the physics world
Capsule* capsule = new Capsule(true, CAPSULE_RADIUS, CAPSULE_HEIGHT, CAPSULE_MASS,
mPhysicsCommon, mPhysicsWorld, meshFolderPath);
capsule->getRigidBody()->getMaterial().setRollingResistance(rp3d::decimal(0.08));
@ -138,8 +138,8 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& sett
// Create all the convex meshes of the scene
for (int i = 0; i<NB_MESHES; i++) {
// Create a convex mesh and a corresponding rigid in the dynamics world
ConvexMesh* mesh = new ConvexMesh(MESH_MASS, mPhysicsCommon, getDynamicsWorld(), meshFolderPath + "convexmesh.obj");
// Create a convex mesh and a corresponding rigid in the physics world
ConvexMesh* mesh = new ConvexMesh(MESH_MASS, mPhysicsCommon, mPhysicsWorld, meshFolderPath + "convexmesh.obj");
// Set the box color
mesh->setColor(mObjectColorDemo);
@ -159,8 +159,8 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& sett
// Position
rp3d::decimal mass = 1.0;
// Create a convex mesh and a corresponding rigid in the dynamics world
mConcaveMesh = new ConcaveMesh(mass, mPhysicsCommon, getDynamicsWorld(), meshFolderPath + "city.obj");
// Create a convex mesh and a corresponding rigid in the physics world
mConcaveMesh = new ConcaveMesh(mass, mPhysicsCommon, mPhysicsWorld, meshFolderPath + "city.obj");
// Set the mesh as beeing static
mConcaveMesh->getRigidBody()->setType(rp3d::BodyType::STATIC);
@ -177,15 +177,15 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& sett
material.setFrictionCoefficient(rp3d::decimal(0.1));
// Get the physics engine parameters
mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled();
rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity();
mEngineSettings.isGravityEnabled = mPhysicsWorld->isGravityEnabled();
rp3d::Vector3 gravityVector = mPhysicsWorld->getGravity();
mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z);
mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep();
mEngineSettings.isSleepingEnabled = mPhysicsWorld->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = mPhysicsWorld->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = mPhysicsWorld->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = mPhysicsWorld->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = mPhysicsWorld->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = mPhysicsWorld->getTimeBeforeSleep();
}
// Destructor
@ -194,15 +194,15 @@ ConcaveMeshScene::~ConcaveMeshScene() {
// Destroy all the physics objects of the scene
for (std::vector<PhysicsObject*>::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) {
// Destroy the corresponding rigid body from the dynamics world
getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody());
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyRigidBody((*it)->getRigidBody());
// Destroy the object
delete (*it);
}
// Destroy the dynamics world
mPhysicsCommon.destroyDynamicsWorld(getDynamicsWorld());
// Destroy the physics world
mPhysicsCommon.destroyPhysicsWorld(mPhysicsWorld);
}
// Reset the scene

View File

@ -32,7 +32,7 @@ using namespace cubesscene;
// Constructor
CubesScene::CubesScene(const std::string& name, EngineSettings& settings)
: SceneDemo(name, settings, SCENE_RADIUS) {
: SceneDemo(name, settings, true, SCENE_RADIUS) {
// Compute the radius and the center of the scene
openglframework::Vector3 center(0, 5, 0);
@ -40,22 +40,22 @@ CubesScene::CubesScene(const std::string& name, EngineSettings& settings)
// Set the center of the scene
setScenePosition(center, SCENE_RADIUS);
// Gravity vector in the dynamics world
// Gravity vector in the physics world
rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0);
rp3d::WorldSettings worldSettings;
rp3d::PhysicsWorld::WorldSettings worldSettings;
worldSettings.worldName = name;
// Create the dynamics world for the physics simulation
rp3d::DynamicsWorld* dynamicsWorld = mPhysicsCommon.createDynamicsWorld(gravity, worldSettings);
dynamicsWorld->setEventListener(this);
mPhysicsWorld = dynamicsWorld;
// Create the physics world for the physics simulation
rp3d::PhysicsWorld* physicsWorld = mPhysicsCommon.createPhysicsWorld(worldSettings);
physicsWorld->setEventListener(this);
mPhysicsWorld = physicsWorld;
// Create all the cubes of the scene
for (int i=0; i<NB_CUBES; i++) {
// Create a cube and a corresponding rigid in the dynamics world
Box* cube = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
// Create a cube and a corresponding rigid in the physics world
Box* cube = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Set the box color
cube->setColor(mObjectColorDemo);
@ -73,7 +73,7 @@ CubesScene::CubesScene(const std::string& name, EngineSettings& settings)
// ------------------------- FLOOR ----------------------- //
// Create the floor
mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mFloor->setColor(mFloorColorDemo);
mFloor->setSleepingColor(mFloorColorDemo);
@ -82,15 +82,15 @@ CubesScene::CubesScene(const std::string& name, EngineSettings& settings)
mPhysicsObjects.push_back(mFloor);
// Get the physics engine parameters
mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled();
rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity();
mEngineSettings.isGravityEnabled = mPhysicsWorld->isGravityEnabled();
rp3d::Vector3 gravityVector = mPhysicsWorld->getGravity();
mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z);
mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep();
mEngineSettings.isSleepingEnabled = mPhysicsWorld->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = mPhysicsWorld->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = mPhysicsWorld->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = mPhysicsWorld->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = mPhysicsWorld->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = mPhysicsWorld->getTimeBeforeSleep();
}
// Destructor
@ -99,21 +99,21 @@ CubesScene::~CubesScene() {
// Destroy all the cubes of the scene
for (std::vector<Box*>::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) {
// Destroy the corresponding rigid body from the dynamics world
getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody());
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyRigidBody((*it)->getRigidBody());
// Destroy the cube
delete (*it);
}
// Destroy the rigid body of the floor
getDynamicsWorld()->destroyRigidBody(mFloor->getRigidBody());
mPhysicsWorld->destroyRigidBody(mFloor->getRigidBody());
// Destroy the floor
delete mFloor;
// Destroy the dynamics world
mPhysicsCommon.destroyDynamicsWorld(getDynamicsWorld());
// Destroy the physics world
mPhysicsCommon.destroyPhysicsWorld(mPhysicsWorld);
}
// Reset the scene

View File

@ -32,7 +32,7 @@ using namespace cubestackscene;
// Constructor
CubeStackScene::CubeStackScene(const std::string& name, EngineSettings& settings)
: SceneDemo(name, settings, SCENE_RADIUS) {
: SceneDemo(name, settings, true, SCENE_RADIUS) {
// Compute the radius and the center of the scene
openglframework::Vector3 center(0, 5, 0);
@ -40,24 +40,24 @@ CubeStackScene::CubeStackScene(const std::string& name, EngineSettings& settings
// Set the center of the scene
setScenePosition(center, SCENE_RADIUS);
// Gravity vector in the dynamics world
// Gravity vector in the physics world
rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0);
rp3d::WorldSettings worldSettings;
rp3d::PhysicsWorld::WorldSettings worldSettings;
worldSettings.worldName = name;
// Create the dynamics world for the physics simulation
rp3d::DynamicsWorld* dynamicsWorld = mPhysicsCommon.createDynamicsWorld(gravity, worldSettings);
dynamicsWorld->setEventListener(this);
mPhysicsWorld = dynamicsWorld;
// Create the physics world for the physics simulation
rp3d::PhysicsWorld* physicsWorld = mPhysicsCommon.createPhysicsWorld(worldSettings);
physicsWorld->setEventListener(this);
mPhysicsWorld = physicsWorld;
// Create all the cubes of the scene
for (int i=1; i<=NB_FLOORS; i++) {
for (int j=0; j<i; j++) {
// Create a cube and a corresponding rigid in the dynamics world
Box* cube = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
// Create a cube and a corresponding rigid in the physics world
Box* cube = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Set the box color
cube->setColor(mObjectColorDemo);
@ -76,7 +76,7 @@ CubeStackScene::CubeStackScene(const std::string& name, EngineSettings& settings
// ------------------------- FLOOR ----------------------- //
// Create the floor
mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mFloor->setColor(mFloorColorDemo);
mFloor->setSleepingColor(mFloorColorDemo);
@ -85,15 +85,15 @@ CubeStackScene::CubeStackScene(const std::string& name, EngineSettings& settings
mPhysicsObjects.push_back(mFloor);
// Get the physics engine parameters
mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled();
rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity();
mEngineSettings.isGravityEnabled = mPhysicsWorld->isGravityEnabled();
rp3d::Vector3 gravityVector = mPhysicsWorld->getGravity();
mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z);
mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep();
mEngineSettings.isSleepingEnabled = mPhysicsWorld->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = mPhysicsWorld->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = mPhysicsWorld->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = mPhysicsWorld->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = mPhysicsWorld->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = mPhysicsWorld->getTimeBeforeSleep();
}
// Destructor
@ -102,21 +102,21 @@ CubeStackScene::~CubeStackScene() {
// Destroy all the cubes of the scene
for (std::vector<Box*>::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) {
// Destroy the corresponding rigid body from the dynamics world
getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody());
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyRigidBody((*it)->getRigidBody());
// Destroy the cube
delete (*it);
}
// Destroy the rigid body of the floor
getDynamicsWorld()->destroyRigidBody(mFloor->getRigidBody());
mPhysicsWorld->destroyRigidBody(mFloor->getRigidBody());
// Destroy the floor
delete mFloor;
// Destroy the dynamics world
mPhysicsCommon.destroyDynamicsWorld(getDynamicsWorld());
// Destroy the physics world
mPhysicsCommon.destroyPhysicsWorld(mPhysicsWorld);
}
// Reset the scene

View File

@ -32,7 +32,7 @@ using namespace heightfieldscene;
// Constructor
HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& settings)
: SceneDemo(name, settings, SCENE_RADIUS) {
: SceneDemo(name, settings, true, SCENE_RADIUS) {
std::string meshFolderPath("meshes/");
@ -42,21 +42,21 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett
// Set the center of the scene
setScenePosition(center, SCENE_RADIUS);
// Gravity vector in the dynamics world
// Gravity vector in the physics world
rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0);
rp3d::WorldSettings worldSettings;
rp3d::PhysicsWorld::WorldSettings worldSettings;
worldSettings.worldName = name;
// Create the dynamics world for the physics simulation
rp3d::DynamicsWorld* dynamicsWorld = mPhysicsCommon.createDynamicsWorld(gravity, worldSettings);
dynamicsWorld->setEventListener(this);
mPhysicsWorld = dynamicsWorld;
// Create the physics world for the physics simulation
rp3d::PhysicsWorld* physicsWorld = mPhysicsCommon.createPhysicsWorld(worldSettings);
physicsWorld->setEventListener(this);
mPhysicsWorld = physicsWorld;
for (int i = 0; i<NB_COMPOUND_SHAPES; i++) {
// Create a convex mesh and a corresponding rigid in the dynamics world
Dumbbell* dumbbell = new Dumbbell(mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a convex mesh and a corresponding rigid in the physics world
Dumbbell* dumbbell = new Dumbbell(true, mPhysicsCommon, mPhysicsWorld, meshFolderPath);
// Set the box color
dumbbell->setColor(mObjectColorDemo);
@ -74,8 +74,8 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett
// Create all the boxes of the scene
for (int i = 0; i<NB_BOXES; i++) {
// Create a sphere and a corresponding rigid in the dynamics world
Box* box = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
// Create a sphere and a corresponding rigid in the physics world
Box* box = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Set the box color
box->setColor(mObjectColorDemo);
@ -93,8 +93,8 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett
// Create all the spheres of the scene
for (int i = 0; i<NB_SPHERES; i++) {
// Create a sphere and a corresponding rigid in the dynamics world
Sphere* sphere = new Sphere(SPHERE_RADIUS, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a sphere and a corresponding rigid in the physics world
Sphere* sphere = new Sphere(SPHERE_RADIUS, BOX_MASS, mPhysicsCommon, mPhysicsWorld, meshFolderPath);
// Add some rolling resistance
sphere->getRigidBody()->getMaterial().setRollingResistance(0.08f);
@ -115,9 +115,9 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett
// Create all the capsules of the scene
for (int i = 0; i<NB_CAPSULES; i++) {
// Create a cylinder and a corresponding rigid in the dynamics world
Capsule* capsule = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, CAPSULE_MASS,
mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a cylinder and a corresponding rigid in the physics world
Capsule* capsule = new Capsule(true, CAPSULE_RADIUS, CAPSULE_HEIGHT, CAPSULE_MASS,
mPhysicsCommon, mPhysicsWorld, meshFolderPath);
capsule->getRigidBody()->getMaterial().setRollingResistance(0.08f);
@ -137,8 +137,8 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett
// Create all the convex meshes of the scene
for (int i = 0; i<NB_MESHES; i++) {
// Create a convex mesh and a corresponding rigid in the dynamics world
ConvexMesh* mesh = new ConvexMesh(MESH_MASS, mPhysicsCommon, getDynamicsWorld(), meshFolderPath + "convexmesh.obj");
// Create a convex mesh and a corresponding rigid in the physics world
ConvexMesh* mesh = new ConvexMesh(MESH_MASS, mPhysicsCommon, mPhysicsWorld, meshFolderPath + "convexmesh.obj");
// Set the box color
mesh->setColor(mObjectColorDemo);
@ -158,8 +158,8 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett
// Position
rp3d::decimal mass = 1.0;
// Create a convex mesh and a corresponding rigid in the dynamics world
mHeightField = new HeightField(mass, mPhysicsCommon, getDynamicsWorld());
// Create a convex mesh and a corresponding rigid in the physics world
mHeightField = new HeightField(mass, mPhysicsCommon, mPhysicsWorld);
// Set the mesh as beeing static
mHeightField->getRigidBody()->setType(rp3d::BodyType::STATIC);
@ -176,15 +176,15 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett
material.setFrictionCoefficient(0.1f);
// Get the physics engine parameters
mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled();
rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity();
mEngineSettings.isGravityEnabled = mPhysicsWorld->isGravityEnabled();
rp3d::Vector3 gravityVector = mPhysicsWorld->getGravity();
mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z);
mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep();
mEngineSettings.isSleepingEnabled = mPhysicsWorld->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = mPhysicsWorld->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = mPhysicsWorld->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = mPhysicsWorld->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = mPhysicsWorld->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = mPhysicsWorld->getTimeBeforeSleep();
}
// Destructor
@ -193,15 +193,15 @@ HeightFieldScene::~HeightFieldScene() {
// Destroy all the physics objects of the scene
for (std::vector<PhysicsObject*>::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) {
// Destroy the corresponding rigid body from the dynamics world
getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody());
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyRigidBody((*it)->getRigidBody());
// Destroy the object
delete (*it);
}
// Destroy the dynamics world
mPhysicsCommon.destroyDynamicsWorld(getDynamicsWorld());
// Destroy the physics world
mPhysicsCommon.destroyPhysicsWorld(mPhysicsWorld);
}
// Reset the scene

View File

@ -33,7 +33,7 @@ using namespace jointsscene;
// Constructor
JointsScene::JointsScene(const std::string& name, EngineSettings& settings)
: SceneDemo(name, settings, SCENE_RADIUS) {
: SceneDemo(name, settings, true, SCENE_RADIUS) {
// Compute the radius and the center of the scene
openglframework::Vector3 center(0, 5, 0);
@ -41,16 +41,16 @@ JointsScene::JointsScene(const std::string& name, EngineSettings& settings)
// Set the center of the scene
setScenePosition(center, SCENE_RADIUS);
// Gravity vector in the dynamics world
// Gravity vector in the physics world
rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0);
rp3d::WorldSettings worldSettings;
rp3d::PhysicsWorld::WorldSettings worldSettings;
worldSettings.worldName = name;
// Create the dynamics world for the physics simulation
rp3d::DynamicsWorld* dynamicsWorld = mPhysicsCommon.createDynamicsWorld(gravity, worldSettings);
dynamicsWorld->setEventListener(this);
mPhysicsWorld = dynamicsWorld;
// Create the physics world for the physics simulation
rp3d::PhysicsWorld* physicsWorld = mPhysicsCommon.createPhysicsWorld(worldSettings);
physicsWorld->setEventListener(this);
mPhysicsWorld = physicsWorld;
// Create the Ball-and-Socket joint
createBallAndSocketJoints();
@ -68,37 +68,37 @@ JointsScene::JointsScene(const std::string& name, EngineSettings& settings)
createFloor();
// Get the physics engine parameters
mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled();
rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity();
mEngineSettings.isGravityEnabled = mPhysicsWorld->isGravityEnabled();
rp3d::Vector3 gravityVector = mPhysicsWorld->getGravity();
mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z);
mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep();
mEngineSettings.isSleepingEnabled = mPhysicsWorld->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = mPhysicsWorld->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = mPhysicsWorld->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = mPhysicsWorld->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = mPhysicsWorld->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = mPhysicsWorld->getTimeBeforeSleep();
}
// Destructor
JointsScene::~JointsScene() {
// Destroy the joints
getDynamicsWorld()->destroyJoint(mSliderJoint);
getDynamicsWorld()->destroyJoint(mPropellerHingeJoint);
getDynamicsWorld()->destroyJoint(mFixedJoint1);
getDynamicsWorld()->destroyJoint(mFixedJoint2);
mPhysicsWorld->destroyJoint(mSliderJoint);
mPhysicsWorld->destroyJoint(mPropellerHingeJoint);
mPhysicsWorld->destroyJoint(mFixedJoint1);
mPhysicsWorld->destroyJoint(mFixedJoint2);
for (int i=0; i<NB_BALLSOCKETJOINT_BOXES-1; i++) {
getDynamicsWorld()->destroyJoint(mBallAndSocketJoints[i]);
mPhysicsWorld->destroyJoint(mBallAndSocketJoints[i]);
}
// Destroy all the rigid bodies of the scene
getDynamicsWorld()->destroyRigidBody(mSliderJointBottomBox->getRigidBody());
getDynamicsWorld()->destroyRigidBody(mSliderJointTopBox->getRigidBody());
getDynamicsWorld()->destroyRigidBody(mPropellerBox->getRigidBody());
getDynamicsWorld()->destroyRigidBody(mFixedJointBox1->getRigidBody());
getDynamicsWorld()->destroyRigidBody(mFixedJointBox2->getRigidBody());
mPhysicsWorld->destroyRigidBody(mSliderJointBottomBox->getRigidBody());
mPhysicsWorld->destroyRigidBody(mSliderJointTopBox->getRigidBody());
mPhysicsWorld->destroyRigidBody(mPropellerBox->getRigidBody());
mPhysicsWorld->destroyRigidBody(mFixedJointBox1->getRigidBody());
mPhysicsWorld->destroyRigidBody(mFixedJointBox2->getRigidBody());
for (int i=0; i<NB_BALLSOCKETJOINT_BOXES; i++) {
getDynamicsWorld()->destroyRigidBody(mBallAndSocketJointChainBoxes[i]->getRigidBody());
mPhysicsWorld->destroyRigidBody(mBallAndSocketJointChainBoxes[i]->getRigidBody());
}
delete mSliderJointBottomBox;
@ -111,11 +111,11 @@ JointsScene::~JointsScene() {
}
// Destroy the floor
getDynamicsWorld()->destroyRigidBody(mFloor->getRigidBody());
mPhysicsWorld->destroyRigidBody(mFloor->getRigidBody());
delete mFloor;
// Destroy the dynamics world
mPhysicsCommon.destroyDynamicsWorld(getDynamicsWorld());
// Destroy the physics world
mPhysicsCommon.destroyPhysicsWorld(mPhysicsWorld);
}
// Update the physics world (take a simulation step)
@ -143,7 +143,7 @@ void JointsScene::reset() {
rp3d::Quaternion initOrientation = rp3d::Quaternion::identity();
rp3d::Transform transform(initPosition, initOrientation);
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
mBallAndSocketJointChainBoxes[i]->setTransform(transform);
positionBox.y -= boxDimension.y + 0.5f;
@ -157,7 +157,7 @@ void JointsScene::reset() {
rp3d::Quaternion initOrientation = rp3d::Quaternion::identity();
rp3d::Transform transformBottomBox(initPosition, initOrientation);
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
mSliderJointBottomBox->setTransform(transformBottomBox);
// Position of the box
@ -166,7 +166,7 @@ void JointsScene::reset() {
initOrientation = rp3d::Quaternion::identity();
rp3d::Transform transformTopBox(initPosition, initOrientation);
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
mSliderJointTopBox->setTransform(transformTopBox);
// --------------- Propeller Hinge joint --------------- //
@ -177,7 +177,7 @@ void JointsScene::reset() {
initOrientation = rp3d::Quaternion::identity();
rp3d::Transform transformHingeBox(initPosition, initOrientation);
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
mPropellerBox->setTransform(transformHingeBox);
// --------------- Fixed joint --------------- //
@ -188,7 +188,7 @@ void JointsScene::reset() {
initOrientation = rp3d::Quaternion::identity();
rp3d::Transform transformFixedBox1(initPosition, initOrientation);
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
mFixedJointBox1->setTransform(transformFixedBox1);
// Position of the box
@ -197,7 +197,7 @@ void JointsScene::reset() {
initOrientation = rp3d::Quaternion::identity();
rp3d::Transform transformFixedBox2(initPosition, initOrientation);
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
mFixedJointBox2->setTransform(transformFixedBox2);
}
@ -212,9 +212,9 @@ void JointsScene::createBallAndSocketJoints() {
for (int i=0; i<NB_BALLSOCKETJOINT_BOXES; i++) {
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
mBallAndSocketJointChainBoxes[i] = new Box(boxDimension, boxMass,
mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mBallAndSocketJointChainBoxes[i]->setTransform(rp3d::Transform(positionBox, rp3d::Quaternion::identity()));
// Set the box color
@ -250,9 +250,9 @@ void JointsScene::createBallAndSocketJoints() {
const rp3d::Vector3 anchorPointWorldSpace = 0.5 * (body1Position + body2Position);
rp3d::BallAndSocketJointInfo jointInfo(body1, body2, anchorPointWorldSpace);
// Create the joint in the dynamics world
// Create the joint in the physics world
mBallAndSocketJoints[i] = dynamic_cast<rp3d::BallAndSocketJoint*>(
getDynamicsWorld()->createJoint(jointInfo));
mPhysicsWorld->createJoint(jointInfo));
}
}
@ -264,9 +264,9 @@ void JointsScene::createSliderJoint() {
// Position of the box
rp3d::Vector3 positionBox1(0, 2.1f, 0);
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
openglframework::Vector3 box1Dimension(2, 4, 2);
mSliderJointBottomBox = new Box(box1Dimension , BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
mSliderJointBottomBox = new Box(box1Dimension , BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mSliderJointBottomBox->setTransform(rp3d::Transform(positionBox1, rp3d::Quaternion::identity()));
// Set the box color
@ -286,9 +286,9 @@ void JointsScene::createSliderJoint() {
// Position of the box
rp3d::Vector3 positionBox2(0, 4.2f, 0);
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
openglframework::Vector3 box2Dimension(1.5f, 4, 1.5f);
mSliderJointTopBox = new Box(box2Dimension, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
mSliderJointTopBox = new Box(box2Dimension, BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mSliderJointTopBox->setTransform(rp3d::Transform(positionBox2, rp3d::Quaternion::identity()));
// Set the box color
@ -316,8 +316,8 @@ void JointsScene::createSliderJoint() {
jointInfo.maxMotorForce = 10000.0;
jointInfo.isCollisionEnabled = false;
// Create the joint in the dynamics world
mSliderJoint = dynamic_cast<rp3d::SliderJoint*>(getDynamicsWorld()->createJoint(jointInfo));
// Create the joint in the physics world
mSliderJoint = dynamic_cast<rp3d::SliderJoint*>(mPhysicsWorld->createJoint(jointInfo));
}
/// Create the boxes and joint for the Hinge joint example
@ -328,9 +328,9 @@ void JointsScene::createPropellerHingeJoint() {
// Position of the box
rp3d::Vector3 positionBox1(0, 7, 0);
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
openglframework::Vector3 boxDimension(10, 1, 1);
mPropellerBox = new Box(boxDimension, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
mPropellerBox = new Box(boxDimension, BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mPropellerBox->setTransform(rp3d::Transform(positionBox1, rp3d::Quaternion::identity()));
// Set the box color
@ -357,8 +357,8 @@ void JointsScene::createPropellerHingeJoint() {
jointInfo.maxMotorTorque = rp3d::decimal(60.0);
jointInfo.isCollisionEnabled = false;
// Create the joint in the dynamics world
mPropellerHingeJoint = dynamic_cast<rp3d::HingeJoint*>(getDynamicsWorld()->createJoint(jointInfo));
// Create the joint in the physics world
mPropellerHingeJoint = dynamic_cast<rp3d::HingeJoint*>(mPhysicsWorld->createJoint(jointInfo));
}
/// Create the boxes and joints for the fixed joints
@ -369,9 +369,9 @@ void JointsScene::createFixedJoints() {
// Position of the box
rp3d::Vector3 positionBox1(5, 7, 0);
// Create a box and a corresponding rigid in the dynamics world
// Create a box and a corresponding rigid in the physics world
openglframework::Vector3 boxDimension(1.5, 1.5, 1.5);
mFixedJointBox1 = new Box(boxDimension, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
mFixedJointBox1 = new Box(boxDimension, BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mFixedJointBox1->setTransform(rp3d::Transform(positionBox1, rp3d::Quaternion::identity()));
// Set the box color
@ -388,8 +388,8 @@ void JointsScene::createFixedJoints() {
// Position of the box
rp3d::Vector3 positionBox2(-5, 7, 0);
// Create a box and a corresponding rigid in the dynamics world
mFixedJointBox2 = new Box(boxDimension, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
// Create a box and a corresponding rigid in the physics world
mFixedJointBox2 = new Box(boxDimension, BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mFixedJointBox2->setTransform(rp3d::Transform(positionBox2, rp3d::Quaternion::identity()));
// Set the box color
@ -410,8 +410,8 @@ void JointsScene::createFixedJoints() {
rp3d::FixedJointInfo jointInfo1(body1, propellerBody, anchorPointWorldSpace1);
jointInfo1.isCollisionEnabled = false;
// Create the joint in the dynamics world
mFixedJoint1 = dynamic_cast<rp3d::FixedJoint*>(getDynamicsWorld()->createJoint(jointInfo1));
// Create the joint in the physics world
mFixedJoint1 = dynamic_cast<rp3d::FixedJoint*>(mPhysicsWorld->createJoint(jointInfo1));
// --------------- Create the second fixed joint --------------- //
@ -421,8 +421,8 @@ void JointsScene::createFixedJoints() {
rp3d::FixedJointInfo jointInfo2(body2, propellerBody, anchorPointWorldSpace2);
jointInfo2.isCollisionEnabled = false;
// Create the joint in the dynamics world
mFixedJoint2 = dynamic_cast<rp3d::FixedJoint*>(getDynamicsWorld()->createJoint(jointInfo2));
// Create the joint in the physics world
mFixedJoint2 = dynamic_cast<rp3d::FixedJoint*>(mPhysicsWorld->createJoint(jointInfo2));
}
// Create the floor
@ -430,7 +430,7 @@ void JointsScene::createFloor() {
// Create the floor
rp3d::Vector3 floorPosition(0, 0, 0);
mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Set the box color
mFloor->setColor(mFloorColorDemo);

View File

@ -32,7 +32,7 @@ using namespace pilescene;
// Constructor
PileScene::PileScene(const std::string& name, EngineSettings& settings)
: SceneDemo(name, settings, SCENE_RADIUS) {
: SceneDemo(name, settings, true, SCENE_RADIUS) {
std::string meshFolderPath("meshes/");
@ -42,19 +42,19 @@ PileScene::PileScene(const std::string& name, EngineSettings& settings)
// Set the center of the scene
setScenePosition(center, SCENE_RADIUS);
// Gravity vector in the dynamics world
// Gravity vector in the physics world
rp3d::Vector3 gravity(0, -9.81f, 0);
rp3d::WorldSettings worldSettings;
rp3d::PhysicsWorld::WorldSettings worldSettings;
worldSettings.worldName = name;
// Create the dynamics world for the physics simulation
mPhysicsWorld = mPhysicsCommon.createDynamicsWorld(gravity, worldSettings);
// Create the physics world for the physics simulation
mPhysicsWorld = mPhysicsCommon.createPhysicsWorld(worldSettings);
for (int i=0; i<NB_COMPOUND_SHAPES; i++) {
// Create a convex mesh and a corresponding rigid in the dynamics world
Dumbbell* dumbbell = new Dumbbell(mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a convex mesh and a corresponding rigid in the physics world
Dumbbell* dumbbell = new Dumbbell(true, mPhysicsCommon, mPhysicsWorld, meshFolderPath);
// Set the box color
dumbbell->setColor(mObjectColorDemo);
@ -72,8 +72,8 @@ PileScene::PileScene(const std::string& name, EngineSettings& settings)
// Create all the boxes of the scene
for (int i=0; i<NB_BOXES; i++) {
// Create a sphere and a corresponding rigid in the dynamics world
Box* box = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), mMeshFolderPath);
// Create a sphere and a corresponding rigid in the physics world
Box* box = new Box(BOX_SIZE, BOX_MASS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Set the box color
box->setColor(mObjectColorDemo);
@ -91,8 +91,8 @@ PileScene::PileScene(const std::string& name, EngineSettings& settings)
// Create all the spheres of the scene
for (int i=0; i<NB_SPHERES; i++) {
// Create a sphere and a corresponding rigid in the dynamics world
Sphere* sphere = new Sphere(SPHERE_RADIUS, BOX_MASS, mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a sphere and a corresponding rigid in the physics world
Sphere* sphere = new Sphere(SPHERE_RADIUS, BOX_MASS, mPhysicsCommon, mPhysicsWorld, meshFolderPath);
// Add some rolling resistance
sphere->getRigidBody()->getMaterial().setRollingResistance(rp3d::decimal(0.08));
@ -113,9 +113,9 @@ PileScene::PileScene(const std::string& name, EngineSettings& settings)
// Create all the capsules of the scene
for (int i=0; i<NB_CAPSULES; i++) {
// Create a cylinder and a corresponding rigid in the dynamics world
Capsule* capsule = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, CAPSULE_MASS,
mPhysicsCommon, getDynamicsWorld(), meshFolderPath);
// Create a cylinder and a corresponding rigid in the physics world
Capsule* capsule = new Capsule(true, CAPSULE_RADIUS, CAPSULE_HEIGHT, CAPSULE_MASS,
mPhysicsCommon, mPhysicsWorld, meshFolderPath);
capsule->getRigidBody()->getMaterial().setRollingResistance(rp3d::decimal(0.08f));
@ -135,8 +135,8 @@ PileScene::PileScene(const std::string& name, EngineSettings& settings)
// Create all the convex meshes of the scene
for (int i=0; i<NB_MESHES; i++) {
// Create a convex mesh and a corresponding rigid in the dynamics world
ConvexMesh* mesh = new ConvexMesh(MESH_MASS, mPhysicsCommon, getDynamicsWorld(), meshFolderPath + "convexmesh.obj");
// Create a convex mesh and a corresponding rigid in the physics world
ConvexMesh* mesh = new ConvexMesh(MESH_MASS, mPhysicsCommon, mPhysicsWorld, meshFolderPath + "convexmesh.obj");
// Set the box color
mesh->setColor(mObjectColorDemo);
@ -156,8 +156,8 @@ PileScene::PileScene(const std::string& name, EngineSettings& settings)
// Position
rp3d::decimal mass = 1.0;
// Create a convex mesh and a corresponding rigid in the dynamics world
mSandbox = new ConcaveMesh(mass, mPhysicsCommon, getDynamicsWorld(), meshFolderPath + "sandbox.obj");
// Create a convex mesh and a corresponding rigid in the physics world
mSandbox = new ConcaveMesh(mass, mPhysicsCommon, mPhysicsWorld, meshFolderPath + "sandbox.obj");
// Set the mesh as beeing static
mSandbox->getRigidBody()->setType(rp3d::BodyType::STATIC);
@ -174,15 +174,15 @@ PileScene::PileScene(const std::string& name, EngineSettings& settings)
material.setFrictionCoefficient(rp3d::decimal(0.1));
// Get the physics engine parameters
mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled();
rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity();
mEngineSettings.isGravityEnabled = mPhysicsWorld->isGravityEnabled();
rp3d::Vector3 gravityVector = mPhysicsWorld->getGravity();
mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z);
mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep();
mEngineSettings.isSleepingEnabled = mPhysicsWorld->isSleepingEnabled();
mEngineSettings.sleepLinearVelocity = mPhysicsWorld->getSleepLinearVelocity();
mEngineSettings.sleepAngularVelocity = mPhysicsWorld->getSleepAngularVelocity();
mEngineSettings.nbPositionSolverIterations = mPhysicsWorld->getNbIterationsPositionSolver();
mEngineSettings.nbVelocitySolverIterations = mPhysicsWorld->getNbIterationsVelocitySolver();
mEngineSettings.timeBeforeSleep = mPhysicsWorld->getTimeBeforeSleep();
}
// Destructor
@ -191,15 +191,15 @@ PileScene::~PileScene() {
// Destroy all the physics objects of the scene
for (std::vector<PhysicsObject*>::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) {
// Destroy the corresponding rigid body from the dynamics world
getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody());
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyRigidBody((*it)->getRigidBody());
// Destroy the object
delete (*it);
}
// Destroy the dynamics world
mPhysicsCommon.destroyDynamicsWorld(getDynamicsWorld());
// Destroy the physics world
mPhysicsCommon.destroyPhysicsWorld(mPhysicsWorld);
}
/// Reset the scene

View File

@ -44,16 +44,16 @@ RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings)
// Set the center of the scene
setScenePosition(center, SCENE_RADIUS);
rp3d::WorldSettings worldSettings;
rp3d::PhysicsWorld::WorldSettings worldSettings;
worldSettings.worldName = name;
// Create the dynamics world for the physics simulation
mPhysicsWorld = mPhysicsCommon.createCollisionWorld(worldSettings);
// Create the physics world for the physics simulation
mPhysicsWorld = mPhysicsCommon.createPhysicsWorld(worldSettings);
// ---------- Dumbbell ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world
mDumbbell = new Dumbbell(mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Create a convex mesh and a corresponding collision body in the physics world
mDumbbell = new Dumbbell(false, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Set the box color
mDumbbell->setColor(mObjectColorDemo);
@ -62,7 +62,7 @@ RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings)
// ---------- Box ---------- //
// Create a box and a corresponding collision body in the dynamics world
// Create a box and a corresponding collision body in the physics world
mBox = new Box(BOX_SIZE, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
mBox->getCollisionBody()->setIsActive(false);
@ -73,7 +73,7 @@ RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings)
// ---------- Sphere ---------- //
// Create a sphere and a corresponding collision body in the dynamics world
// Create a sphere and a corresponding collision body in the physics world
mSphere = new Sphere(SPHERE_RADIUS, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Set the color
@ -84,8 +84,8 @@ RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings)
// ---------- Capsule ---------- //
openglframework::Vector3 position6(0, 0, 0);
// Create a cylinder and a corresponding collision body in the dynamics world
mCapsule = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Create a cylinder and a corresponding collision body in the physics world
mCapsule = new Capsule(false, CAPSULE_RADIUS, CAPSULE_HEIGHT, 1.0, mPhysicsCommon, mPhysicsWorld, mMeshFolderPath);
// Set the color
mCapsule->setColor(mObjectColorDemo);
@ -94,7 +94,7 @@ RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings)
// ---------- Convex Mesh ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world
// Create a convex mesh and a corresponding collision body in the physics world
mConvexMesh = new ConvexMesh(mPhysicsCommon, mPhysicsWorld, mMeshFolderPath + "convexmesh.obj");
// Set the color
@ -104,7 +104,7 @@ RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings)
// ---------- Concave Mesh ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world
// Create a convex mesh and a corresponding collision body in the physics world
mConcaveMesh = new ConcaveMesh(mPhysicsCommon, mPhysicsWorld, mMeshFolderPath + "city.obj");
// Set the color
@ -114,7 +114,7 @@ RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings)
// ---------- Heightfield ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world
// Create a convex mesh and a corresponding collision body in the physics world
mHeightField = new HeightField(mPhysicsCommon, mPhysicsWorld);
// Set the color
@ -207,7 +207,7 @@ void RaycastScene::reset() {
// Destructor
RaycastScene::~RaycastScene() {
// Destroy the box rigid body from the dynamics world
// Destroy the box rigid body from the physics world
mPhysicsWorld->destroyCollisionBody(mBox->getCollisionBody());
delete mBox;
@ -215,31 +215,31 @@ RaycastScene::~RaycastScene() {
mPhysicsWorld->destroyCollisionBody(mSphere->getCollisionBody());
delete mSphere;
// Destroy the corresponding rigid body from the dynamics world
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyCollisionBody(mCapsule->getCollisionBody());
// Destroy the sphere
delete mCapsule;
// Destroy the corresponding rigid body from the dynamics world
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyCollisionBody(mConvexMesh->getCollisionBody());
// Destroy the convex mesh
delete mConvexMesh;
// Destroy the corresponding rigid body from the dynamics world
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyCollisionBody(mDumbbell->getCollisionBody());
// Destroy the dumbbell
delete mDumbbell;
// Destroy the corresponding rigid body from the dynamics world
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody());
// Destroy the convex mesh
delete mConcaveMesh;
// Destroy the corresponding rigid body from the dynamics world
// Destroy the corresponding rigid body from the physics world
mPhysicsWorld->destroyCollisionBody(mHeightField->getCollisionBody());
// Destroy the convex mesh
@ -251,7 +251,7 @@ RaycastScene::~RaycastScene() {
VisualContactPoint::destroyStaticData();
// Destroy the collision world
mPhysicsCommon.destroyCollisionWorld(mPhysicsWorld);
mPhysicsCommon.destroyPhysicsWorld(mPhysicsWorld);
// Destroy the lines
for (std::vector<Line*>::iterator it = mLines.begin(); it != mLines.end();

View File

@ -72,7 +72,7 @@ struct EngineSettings {
EngineSettings defaultSettings;
rp3d::WorldSettings worldSettings;
rp3d::PhysicsWorld::WorldSettings worldSettings;
defaultSettings.timeStep = 1.0f / 60.0f;
defaultSettings.nbVelocitySolverIterations = worldSettings.defaultVelocitySolverNbIterations;
defaultSettings.nbPositionSolverIterations = worldSettings.defaultPositionSolverNbIterations;

View File

@ -39,14 +39,14 @@ openglframework::Color SceneDemo::mSleepingColorDemo = Color(1.0f, 0.25f, 0.25f,
openglframework::Color SceneDemo::mSelectedObjectColorDemo = Color(0.09f, 0.59f, 0.88f, 1.0f);
// Constructor
SceneDemo::SceneDemo(const std::string& name, EngineSettings& settings, float sceneRadius, bool isShadowMappingEnabled)
SceneDemo::SceneDemo(const std::string& name, EngineSettings& settings, bool isPhysicsWorldSimulated, float sceneRadius, bool isShadowMappingEnabled)
: Scene(name, settings, isShadowMappingEnabled), mIsShadowMappingInitialized(false),
mDepthShader("shaders/depth.vert", "shaders/depth.frag"),
mPhongShader("shaders/phong.vert", "shaders/phong.frag"),
mColorShader("shaders/color.vert", "shaders/color.frag"),
mQuadShader("shaders/quad.vert", "shaders/quad.frag"),
mVBOQuad(GL_ARRAY_BUFFER), mMeshFolderPath("meshes/"),
mPhysicsWorld(nullptr) {
mPhysicsWorld(nullptr), mIsPhysicsWorldSimulated(isPhysicsWorldSimulated) {
shadowMapTextureLevel++;
@ -143,10 +143,10 @@ void SceneDemo::updatePhysics() {
// Clear contacts points
mContactPoints.clear();
if (getDynamicsWorld() != nullptr) {
if (mIsPhysicsWorldSimulated) {
// Take a simulation step
getDynamicsWorld()->update(mEngineSettings.timeStep);
mPhysicsWorld->update(mEngineSettings.timeStep);
}
}
@ -474,18 +474,18 @@ void SceneDemo::removeAllVisualContactPoints() {
// Update the engine settings
void SceneDemo::updateEngineSettings() {
if (getDynamicsWorld() != nullptr) {
if (mIsPhysicsWorldSimulated) {
// Update the physics engine parameters
getDynamicsWorld()->setIsGratityEnabled(mEngineSettings.isGravityEnabled);
mPhysicsWorld->setIsGratityEnabled(mEngineSettings.isGravityEnabled);
rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y,
mEngineSettings.gravity.z);
getDynamicsWorld()->setGravity(gravity);
getDynamicsWorld()->enableSleeping(mEngineSettings.isSleepingEnabled);
getDynamicsWorld()->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity);
getDynamicsWorld()->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity);
getDynamicsWorld()->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations);
getDynamicsWorld()->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations);
getDynamicsWorld()->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep);
mPhysicsWorld->setGravity(gravity);
mPhysicsWorld->enableSleeping(mEngineSettings.isSleepingEnabled);
mPhysicsWorld->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity);
mPhysicsWorld->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity);
mPhysicsWorld->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations);
mPhysicsWorld->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations);
mPhysicsWorld->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep);
}
}

View File

@ -106,7 +106,10 @@ class SceneDemo : public Scene {
std::vector<PhysicsObject*> mPhysicsObjects;
rp3d::CollisionWorld* mPhysicsWorld;
rp3d::PhysicsWorld* mPhysicsWorld;
/// True if we need to step the physics simulation each frame
bool mIsPhysicsWorldSimulated;
// -------------------- Methods -------------------- //
@ -132,18 +135,12 @@ class SceneDemo : public Scene {
/// Remove all contact points
void removeAllVisualContactPoints();
/// Return a reference to the dynamics world
rp3d::DynamicsWorld* getDynamicsWorld();
/// Return a reference to the dynamics world
const rp3d::DynamicsWorld* getDynamicsWorld() const;
public:
// -------------------- Methods -------------------- //
/// Constructor
SceneDemo(const std::string& name, EngineSettings& settings, float sceneRadius, bool isShadowMappingEnabled = true);
SceneDemo(const std::string& name, EngineSettings& settings, bool isPhysicsWorldSimulated, float sceneRadius, bool isShadowMappingEnabled = true);
/// Destructor
virtual ~SceneDemo() override;
@ -178,14 +175,4 @@ inline void SceneDemo::setIsShadowMappingEnabled(bool isShadowMappingEnabled) {
}
}
// Return a reference to the dynamics world
inline rp3d::DynamicsWorld* SceneDemo::getDynamicsWorld() {
return dynamic_cast<rp3d::DynamicsWorld*>(mPhysicsWorld);
}
// Return a reference to the dynamics world
inline const rp3d::DynamicsWorld* SceneDemo::getDynamicsWorld() const {
return dynamic_cast<rp3d::DynamicsWorld*>(mPhysicsWorld);
}
#endif