[DOC] Update the comments

This commit is contained in:
Edouard DUPIN 2017-06-16 23:05:25 +02:00
parent cd59604b4b
commit 6c3d49de92
16 changed files with 1036 additions and 1752 deletions

View File

@ -5,7 +5,6 @@
*/ */
#pragma once #pragma once
// Libraries
#include <vector> #include <vector>
#include <set> #include <set>
#include <list> #include <list>
@ -21,194 +20,125 @@
#include <ephysics/memory/MemoryAllocator.hpp> #include <ephysics/memory/MemoryAllocator.hpp>
#include <ephysics/engine/EventListener.hpp> #include <ephysics/engine/EventListener.hpp>
/// Namespace ephysics
namespace ephysics { namespace ephysics {
// Declarations
class CollisionCallback; class CollisionCallback;
// Class CollisionWorld
/** /**
* This class represent a world where it is possible to move bodies * @brief 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 * 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. * world, the bodies movement is not computed using the laws of physics.
*/ */
class CollisionWorld { class CollisionWorld {
protected : protected :
CollisionDetection m_collisionDetection; //!< Reference to the collision detection
// -------------------- Attributes -------------------- // std::set<CollisionBody*> m_bodies; //!< All the bodies (rigid and soft) of the world
bodyindex m_currentBodyID; //!< Current body ID
/// Reference to the collision detection std::vector<uint64_t> m_freeBodiesIDs; //!< List of free ID for rigid bodies
CollisionDetection m_collisionDetection; MemoryAllocator m_memoryAllocator; //!< Memory allocator
EventListener* m_eventListener; //!< Pointer to an event listener object
/// All the bodies (rigid and soft) of the world
std::set<CollisionBody*> m_bodies;
/// Current body ID
bodyindex m_currentBodyID;
/// List of free ID for rigid bodies
std::vector<uint64_t> m_freeBodiesIDs;
/// Memory allocator
MemoryAllocator m_memoryAllocator;
/// Pointer to an event listener object
EventListener* m_eventListener;
// -------------------- Methods -------------------- //
/// Private copy-constructor /// Private copy-constructor
CollisionWorld(const CollisionWorld& world); CollisionWorld(const CollisionWorld& world);
/// Private assignment operator /// Private assignment operator
CollisionWorld& operator=(const CollisionWorld& world); CollisionWorld& operator=(const CollisionWorld& world);
/// Return the next available body ID /// Return the next available body ID
bodyindex computeNextAvailableBodyID(); bodyindex computeNextAvailableBodyID();
/// Reset all the contact manifolds linked list of each body /// Reset all the contact manifolds linked list of each body
void resetContactManifoldListsOfBodies(); void resetContactManifoldListsOfBodies();
public : public :
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
CollisionWorld(); CollisionWorld();
/// Destructor /// Destructor
virtual ~CollisionWorld(); virtual ~CollisionWorld();
/**
/// Return an iterator to the beginning of the bodies of the physics world * @brief Get an iterator to the beginning of the bodies of the physics world
std::set<CollisionBody*>::iterator getBodiesBeginIterator(); * @return An starting iterator to the set of bodies of the world
*/
/// Return an iterator to the end of the bodies of the physics world std::set<CollisionBody*>::iterator getBodiesBeginIterator() {
std::set<CollisionBody*>::iterator getBodiesEndIterator(); return m_bodies.begin();
}
/**
* @brief Get an iterator to the end of the bodies of the physics world
* @return An ending iterator to the set of bodies of the world
*/
std::set<CollisionBody*>::iterator getBodiesEndIterator() {
return m_bodies.end();
}
/// Create a collision body /// Create a collision body
CollisionBody* createCollisionBody(const etk::Transform3D& transform); CollisionBody* createCollisionBody(const etk::Transform3D& transform);
/// Destroy a collision body /// Destroy a collision body
void destroyCollisionBody(CollisionBody* collisionBody); void destroyCollisionBody(CollisionBody* collisionBody);
/**
/// Set the collision dispatch configuration * @brief Set the collision dispatch configuration
void setCollisionDispatch(CollisionDispatch* collisionDispatch); * This can be used to replace default collision detection algorithms by your
* custom algorithm for instance.
/// Ray cast method * @param[in] _CollisionDispatch Pointer to a collision dispatch object describing
void raycast(const Ray& ray, RaycastCallback* raycastCallback, * which collision detection algorithm to use for two given collision shapes
unsigned short raycastWithCategoryMaskBits = 0xFFFF) const; */
void setCollisionDispatch(CollisionDispatch* _collisionDispatch) {
m_collisionDetection.setCollisionDispatch(_collisionDispatch);
}
/**
* @brief 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
*/
void raycast(const Ray& _ray,
RaycastCallback* _raycastCallback,
unsigned short _raycastWithCategoryMaskBitss = 0xFFFF) const {
m_collisionDetection.raycast(_raycastCallback, _ray, _raycastWithCategoryMaskBits);
}
/// Test if the AABBs of two bodies overlap /// Test if the AABBs of two bodies overlap
bool testAABBOverlap(const CollisionBody* body1, bool testAABBOverlap(const CollisionBody* body1,
const CollisionBody* body2) const; const CollisionBody* body2) const;
/**
/// Test if the AABBs of two proxy shapes overlap * @brief Test if the AABBs of two proxy shapes overlap
bool testAABBOverlap(const ProxyShape* shape1, * @param _shape1 Pointer to the first proxy shape to test
const ProxyShape* shape2) const; * @param _shape2 Pointer to the second proxy shape to test
*/
bool testAABBOverlap(const ProxyShape* _shape1,
const ProxyShape* _shape2) const {
return m_collisionDetection.testAABBOverlap(shape1, shape2);
}
/// Test and report collisions between a given shape and all the others /// Test and report collisions between a given shape and all the others
/// shapes of the world /// shapes of the world
virtual void testCollision(const ProxyShape* shape, virtual void testCollision(const ProxyShape* shape,
CollisionCallback* callback); CollisionCallback* callback);
/// Test and report collisions between two given shapes /// Test and report collisions between two given shapes
virtual void testCollision(const ProxyShape* shape1, virtual void testCollision(const ProxyShape* shape1,
const ProxyShape* shape2, const ProxyShape* shape2,
CollisionCallback* callback); CollisionCallback* callback);
/// Test and report collisions between a body and all the others bodies of the /// Test and report collisions between a body and all the others bodies of the
/// world /// world
virtual void testCollision(const CollisionBody* body, virtual void testCollision(const CollisionBody* body,
CollisionCallback* callback); CollisionCallback* callback);
/// Test and report collisions between two bodies /// Test and report collisions between two bodies
virtual void testCollision(const CollisionBody* body1, virtual void testCollision(const CollisionBody* body1,
const CollisionBody* body2, const CollisionBody* body2,
CollisionCallback* callback); CollisionCallback* callback);
/// Test and report collisions between all shapes of the world /// Test and report collisions between all shapes of the world
virtual void testCollision(CollisionCallback* callback); virtual void testCollision(CollisionCallback* callback);
// -------------------- Friendship -------------------- //
friend class CollisionDetection; friend class CollisionDetection;
friend class CollisionBody; friend class CollisionBody;
friend class RigidBody; friend class RigidBody;
friend class ConvexMeshShape; friend class ConvexMeshShape;
}; };
// Return an iterator to the beginning of the bodies of the physics world
/** /**
* @return An starting iterator to the set of bodies of the world * @brief This class can be used to register a callback for collision test queries.
*/
inline std::set<CollisionBody*>::iterator CollisionWorld::getBodiesBeginIterator() {
return m_bodies.begin();
}
// Return an iterator to the end of the bodies of the physics world
/**
* @return An ending iterator to the set of bodies of the world
*/
inline std::set<CollisionBody*>::iterator CollisionWorld::getBodiesEndIterator() {
return m_bodies.end();
}
// 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 void CollisionWorld::setCollisionDispatch(CollisionDispatch* collisionDispatch) {
m_collisionDetection.setCollisionDispatch(collisionDispatch);
}
// 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 {
m_collisionDetection.raycast(raycastCallback, ray, raycastWithCategoryMaskBits);
}
// Test if the AABBs of two proxy shapes overlap
/**
* @param shape1 Pointer to the first proxy shape to test
* @param shape2 Pointer to the second proxy shape to test
* @return
*/
inline bool CollisionWorld::testAABBOverlap(const ProxyShape* shape1,
const ProxyShape* shape2) const {
return m_collisionDetection.testAABBOverlap(shape1, shape2);
}
// Class CollisionCallback
/**
* This class can be used to register a callback for collision test queries.
* You should implement your own class inherited from this one and implement * You should implement your own class inherited from this one and implement
* the notifyRaycastHit() method. This method will be called for each ProxyShape * the notifyRaycastHit() method. This method will be called for each ProxyShape
* that is hit by the ray. * that is hit by the ray.
*/ */
class CollisionCallback { class CollisionCallback {
public: public:
/**
/// Destructor * @brief Virtualisation of the destructor.
virtual ~CollisionCallback() { */
virtual ~CollisionCallback() = default;
} /**
* @brief This method will be called for contact.
/// This method will be called for contact * @param[in] _contactPointInfo Contact information property.
virtual void notifyContact(const ContactPointInfo& contactPointInfo)=0; */
virtual void notifyContact(const ContactPointInfo& _contactPointInfo)=0;
}; };
} }

View File

@ -4,7 +4,6 @@
* @license BSD 3 clauses (see license file) * @license BSD 3 clauses (see license file)
*/ */
// Libraries
#include <ephysics/engine/ConstraintSolver.hpp> #include <ephysics/engine/ConstraintSolver.hpp>
#include <ephysics/engine/Profiler.hpp> #include <ephysics/engine/Profiler.hpp>
@ -13,12 +12,7 @@ using namespace ephysics;
// Constructor // Constructor
ConstraintSolver::ConstraintSolver(const std::map<RigidBody*, uint32_t>& mapBodyToVelocityIndex) ConstraintSolver::ConstraintSolver(const std::map<RigidBody*, uint32_t>& mapBodyToVelocityIndex)
: m_mapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), : m_mapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex),
mIsWarmStartingActive(true), m_constraintSolverData(mapBodyToVelocityIndex) { m_isWarmStartingActive(true), m_constraintSolverData(mapBodyToVelocityIndex) {
}
// Destructor
ConstraintSolver::~ConstraintSolver() {
} }
@ -36,7 +30,7 @@ void ConstraintSolver::initializeForIsland(float dt, Island* island) {
// Initialize the constraint solver data used to initialize and solve the constraints // Initialize the constraint solver data used to initialize and solve the constraints
m_constraintSolverData.timeStep = m_timeStep; m_constraintSolverData.timeStep = m_timeStep;
m_constraintSolverData.isWarmStartingActive = mIsWarmStartingActive; m_constraintSolverData.isWarmStartingActive = m_isWarmStartingActive;
// For each joint of the island // For each joint of the island
Joint** joints = island->getJoints(); Joint** joints = island->getJoints();
@ -46,7 +40,7 @@ void ConstraintSolver::initializeForIsland(float dt, Island* island) {
joints[i]->initBeforeSolve(m_constraintSolverData); joints[i]->initBeforeSolve(m_constraintSolverData);
// Warm-start the constraint if warm-starting is enabled // Warm-start the constraint if warm-starting is enabled
if (mIsWarmStartingActive) { if (m_isWarmStartingActive) {
joints[i]->warmstart(m_constraintSolverData); joints[i]->warmstart(m_constraintSolverData);
} }
} }

View File

@ -5,7 +5,6 @@
*/ */
#pragma once #pragma once
// Libraries
#include <ephysics/configuration.hpp> #include <ephysics/configuration.hpp>
#include <ephysics/mathematics/mathematics.hpp> #include <ephysics/mathematics/mathematics.hpp>
#include <ephysics/constraint/Joint.hpp> #include <ephysics/constraint/Joint.hpp>
@ -14,38 +13,19 @@
#include <set> #include <set>
namespace ephysics { namespace ephysics {
// Structure ConstraintSolverData
/** /**
* This structure contains data from the constraint solver that are used to solve * This structure contains data from the constraint solver that are used to solve
* each joint constraint. * each joint constraint.
*/ */
struct ConstraintSolverData { struct ConstraintSolverData {
public : public :
float timeStep; //!< Current time step of the simulation
/// Current time step of the simulation vec3* linearVelocities; //!< Array with the bodies linear velocities
float timeStep; vec3* angularVelocities; //!< Array with the bodies angular velocities
vec3* positions; //!< Reference to the bodies positions
/// Array with the bodies linear velocities etk::Quaternion* orientations; //!< Reference to the bodies orientations
vec3* linearVelocities; const std::map<RigidBody*, uint32_t>& mapBodyToConstrainedVelocityIndex; //!< Reference to the map that associates rigid body to their index in the constrained velocities array
bool isWarmStartingActive; //!< True if warm starting of the solver is active
/// Array with the bodies angular velocities
vec3* angularVelocities;
/// Reference to the bodies positions
vec3* positions;
/// Reference to the bodies orientations
etk::Quaternion* orientations;
/// Reference to the map that associates rigid body to their index
/// in the constrained velocities array
const std::map<RigidBody*, uint32_t>& mapBodyToConstrainedVelocityIndex;
/// True if warm starting of the solver is active
bool isWarmStartingActive;
/// Constructor /// Constructor
ConstraintSolverData(const std::map<RigidBody*, uint32_t>& refMapBodyToConstrainedVelocityIndex) ConstraintSolverData(const std::map<RigidBody*, uint32_t>& refMapBodyToConstrainedVelocityIndex)
:linearVelocities(NULL), angularVelocities(NULL), :linearVelocities(NULL), angularVelocities(NULL),
@ -53,12 +33,10 @@ struct ConstraintSolverData {
mapBodyToConstrainedVelocityIndex(refMapBodyToConstrainedVelocityIndex){ mapBodyToConstrainedVelocityIndex(refMapBodyToConstrainedVelocityIndex){
} }
}; };
// Class ConstraintSolver
/** /**
* This class represents the constraint solver that is used to solve constraints between * @brief This class represents the constraint solver that is used to solve constraints between
* the rigid bodies. The constraint solver is based on the "Sequential Impulse" technique * the rigid bodies. The constraint solver is based on the "Sequential Impulse" technique
* described by Erin Catto in his GDC slides (http://code.google.com/p/box2d/downloads/list). * described by Erin Catto in his GDC slides (http://code.google.com/p/box2d/downloads/list).
* *
@ -126,53 +104,27 @@ struct ConstraintSolverData {
* contact manifold center. * contact manifold center.
*/ */
class ConstraintSolver { class ConstraintSolver {
private : private :
const std::map<RigidBody*, uint32_t>& m_mapBodyToConstrainedVelocityIndex; //!< Reference to the map that associates rigid body to their index in the constrained velocities array
// -------------------- Attributes -------------------- // float m_timeStep; //!< Current time step
bool m_isWarmStartingActive; //!< True if the warm starting of the solver is active
/// Reference to the map that associates rigid body to their index in ConstraintSolverData m_constraintSolverData; //!< Constraint solver data used to initialize and solve the constraints
/// the constrained velocities array
const std::map<RigidBody*, uint32_t>& m_mapBodyToConstrainedVelocityIndex;
/// Current time step
float m_timeStep;
/// True if the warm starting of the solver is active
bool mIsWarmStartingActive;
/// Constraint solver data used to initialize and solve the constraints
ConstraintSolverData m_constraintSolverData;
public : public :
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
ConstraintSolver(const std::map<RigidBody*, uint32_t>& mapBodyToVelocityIndex); ConstraintSolver(const std::map<RigidBody*, uint32_t>& mapBodyToVelocityIndex);
/// Destructor
~ConstraintSolver();
/// Initialize the constraint solver for a given island /// Initialize the constraint solver for a given island
void initializeForIsland(float dt, Island* island); void initializeForIsland(float dt, Island* island);
/// Solve the constraints /// Solve the constraints
void solveVelocityConstraints(Island* island); void solveVelocityConstraints(Island* island);
/// Solve the position constraints /// Solve the position constraints
void solvePositionConstraints(Island* island); void solvePositionConstraints(Island* island);
/// Return true if the Non-Linear-Gauss-Seidel position correction technique is active /// Return true if the Non-Linear-Gauss-Seidel position correction technique is active
bool getIsNonLinearGaussSeidelPositionCorrectionActive() const; bool getIsNonLinearGaussSeidelPositionCorrectionActive() const;
/// Enable/Disable the Non-Linear-Gauss-Seidel position correction technique. /// Enable/Disable the Non-Linear-Gauss-Seidel position correction technique.
void setIsNonLinearGaussSeidelPositionCorrectionActive(bool isActive); void setIsNonLinearGaussSeidelPositionCorrectionActive(bool isActive);
/// Set the constrained velocities arrays /// Set the constrained velocities arrays
void setConstrainedVelocitiesArrays(vec3* constrainedLinearVelocities, void setConstrainedVelocitiesArrays(vec3* constrainedLinearVelocities,
vec3* constrainedAngularVelocities); vec3* constrainedAngularVelocities);
/// Set the constrained positions/orientations arrays /// Set the constrained positions/orientations arrays
void setConstrainedPositionsArrays(vec3* constrainedPositions, void setConstrainedPositionsArrays(vec3* constrainedPositions,
etk::Quaternion* constrainedOrientations); etk::Quaternion* constrainedOrientations);

View File

@ -22,10 +22,10 @@ const float ContactSolver::SLOP= float(0.01);
// Constructor // Constructor
ContactSolver::ContactSolver(const std::map<RigidBody*, uint32_t>& mapBodyToVelocityIndex) ContactSolver::ContactSolver(const std::map<RigidBody*, uint32_t>& mapBodyToVelocityIndex)
:m_splitLinearVelocities(nullptr), m_splitAngularVelocities(nullptr), :m_splitLinearVelocities(nullptr), m_splitAngularVelocities(nullptr),
mContactConstraints(nullptr), mLinearVelocities(nullptr), mAngularVelocities(nullptr), m_contactConstraints(nullptr), m_linearVelocities(nullptr), m_angularVelocities(nullptr),
m_mapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), m_mapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex),
mIsWarmStartingActive(true), mIsSplitImpulseActive(true), m_isWarmStartingActive(true), m_isSplitImpulseActive(true),
mIsSolveFrictionAtContactManifoldCenterActive(true) { m_isSolveFrictionAtContactManifoldCenterActive(true) {
} }
@ -50,8 +50,8 @@ void ContactSolver::initializeForIsland(float dt, Island* island) {
m_numberContactManifolds = island->getNbContactManifolds(); m_numberContactManifolds = island->getNbContactManifolds();
mContactConstraints = new ContactManifoldSolver[m_numberContactManifolds]; m_contactConstraints = new ContactManifoldSolver[m_numberContactManifolds];
assert(mContactConstraints != nullptr); assert(m_contactConstraints != nullptr);
// For each contact manifold of the island // For each contact manifold of the island
ContactManifold** contactManifolds = island->getContactManifold(); ContactManifold** contactManifolds = island->getContactManifold();
@ -59,7 +59,7 @@ void ContactSolver::initializeForIsland(float dt, Island* island) {
ContactManifold* externalManifold = contactManifolds[i]; ContactManifold* externalManifold = contactManifolds[i];
ContactManifoldSolver& int32_ternalManifold = mContactConstraints[i]; ContactManifoldSolver& int32_ternalManifold = m_contactConstraints[i];
assert(externalManifold->getNbContactPoints() > 0); assert(externalManifold->getNbContactPoints() > 0);
@ -90,7 +90,7 @@ void ContactSolver::initializeForIsland(float dt, Island* island) {
int32_ternalManifold.isBody2DynamicType = body2->getType() == DYNAMIC; int32_ternalManifold.isBody2DynamicType = body2->getType() == DYNAMIC;
// If we solve the friction constraints at the center of the contact manifold // If we solve the friction constraints at the center of the contact manifold
if (mIsSolveFrictionAtContactManifoldCenterActive) { if (m_isSolveFrictionAtContactManifoldCenterActive) {
int32_ternalManifold.frictionPointBody1 = vec3(0.0f,0.0f,0.0f); int32_ternalManifold.frictionPointBody1 = vec3(0.0f,0.0f,0.0f);
int32_ternalManifold.frictionPointBody2 = vec3(0.0f,0.0f,0.0f); int32_ternalManifold.frictionPointBody2 = vec3(0.0f,0.0f,0.0f);
} }
@ -122,14 +122,14 @@ void ContactSolver::initializeForIsland(float dt, Island* island) {
contactPoint.rollingResistanceImpulse = vec3(0.0f,0.0f,0.0f); contactPoint.rollingResistanceImpulse = vec3(0.0f,0.0f,0.0f);
// If we solve the friction constraints at the center of the contact manifold // If we solve the friction constraints at the center of the contact manifold
if (mIsSolveFrictionAtContactManifoldCenterActive) { if (m_isSolveFrictionAtContactManifoldCenterActive) {
int32_ternalManifold.frictionPointBody1 += p1; int32_ternalManifold.frictionPointBody1 += p1;
int32_ternalManifold.frictionPointBody2 += p2; int32_ternalManifold.frictionPointBody2 += p2;
} }
} }
// If we solve the friction constraints at the center of the contact manifold // If we solve the friction constraints at the center of the contact manifold
if (mIsSolveFrictionAtContactManifoldCenterActive) { if (m_isSolveFrictionAtContactManifoldCenterActive) {
int32_ternalManifold.frictionPointBody1 /=static_cast<float>(int32_ternalManifold.nbContacts); int32_ternalManifold.frictionPointBody1 /=static_cast<float>(int32_ternalManifold.nbContacts);
int32_ternalManifold.frictionPointBody2 /=static_cast<float>(int32_ternalManifold.nbContacts); int32_ternalManifold.frictionPointBody2 /=static_cast<float>(int32_ternalManifold.nbContacts);
@ -139,7 +139,7 @@ void ContactSolver::initializeForIsland(float dt, Island* island) {
int32_ternalManifold.oldFrictionvec2 = externalManifold->getFrictionvec2(); int32_ternalManifold.oldFrictionvec2 = externalManifold->getFrictionvec2();
// If warm starting is active // If warm starting is active
if (mIsWarmStartingActive) { if (m_isWarmStartingActive) {
// Initialize the accumulated impulses with the previous step accumulated impulses // Initialize the accumulated impulses with the previous step accumulated impulses
int32_ternalManifold.friction1Impulse = externalManifold->getFrictionImpulse1(); int32_ternalManifold.friction1Impulse = externalManifold->getFrictionImpulse1();
@ -167,22 +167,22 @@ void ContactSolver::initializeContactConstraints() {
// For each contact constraint // For each contact constraint
for (uint32_t c=0; c<m_numberContactManifolds; c++) { for (uint32_t c=0; c<m_numberContactManifolds; c++) {
ContactManifoldSolver& manifold = mContactConstraints[c]; ContactManifoldSolver& manifold = m_contactConstraints[c];
// Get the inertia tensors of both bodies // Get the inertia tensors of both bodies
etk::Matrix3x3& I1 = manifold.inverseInertiaTensorBody1; etk::Matrix3x3& I1 = manifold.inverseInertiaTensorBody1;
etk::Matrix3x3& I2 = manifold.inverseInertiaTensorBody2; etk::Matrix3x3& I2 = manifold.inverseInertiaTensorBody2;
// If we solve the friction constraints at the center of the contact manifold // If we solve the friction constraints at the center of the contact manifold
if (mIsSolveFrictionAtContactManifoldCenterActive) { if (m_isSolveFrictionAtContactManifoldCenterActive) {
manifold.normal = vec3(0.0, 0.0, 0.0); manifold.normal = vec3(0.0, 0.0, 0.0);
} }
// Get the velocities of the bodies // Get the velocities of the bodies
const vec3& v1 = mLinearVelocities[manifold.indexBody1]; const vec3& v1 = m_linearVelocities[manifold.indexBody1];
const vec3& w1 = mAngularVelocities[manifold.indexBody1]; const vec3& w1 = m_angularVelocities[manifold.indexBody1];
const vec3& v2 = mLinearVelocities[manifold.indexBody2]; const vec3& v2 = m_linearVelocities[manifold.indexBody2];
const vec3& w2 = mAngularVelocities[manifold.indexBody2]; const vec3& w2 = m_angularVelocities[manifold.indexBody2];
// For each contact point constraint // For each contact point constraint
for (uint32_t i=0; i<manifold.nbContacts; i++) { for (uint32_t i=0; i<manifold.nbContacts; i++) {
@ -205,7 +205,7 @@ void ContactSolver::initializeContactConstraints() {
0.0f; 0.0f;
// If we do not solve the friction constraints at the center of the contact manifold // If we do not solve the friction constraints at the center of the contact manifold
if (!mIsSolveFrictionAtContactManifoldCenterActive) { if (!m_isSolveFrictionAtContactManifoldCenterActive) {
// Compute the friction vectors // Compute the friction vectors
computeFrictionVectors(deltaV, contactPoint); computeFrictionVectors(deltaV, contactPoint);
@ -246,7 +246,7 @@ void ContactSolver::initializeContactConstraints() {
} }
// If the warm starting of the contact solver is active // If the warm starting of the contact solver is active
if (mIsWarmStartingActive) { if (m_isWarmStartingActive) {
// Get the cached accumulated impulses from the previous step // Get the cached accumulated impulses from the previous step
contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse(); contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse();
@ -259,7 +259,7 @@ void ContactSolver::initializeContactConstraints() {
contactPoint.penetrationSplitImpulse = 0.0; contactPoint.penetrationSplitImpulse = 0.0;
// If we solve the friction constraints at the center of the contact manifold // If we solve the friction constraints at the center of the contact manifold
if (mIsSolveFrictionAtContactManifoldCenterActive) { if (m_isSolveFrictionAtContactManifoldCenterActive) {
manifold.normal += contactPoint.normal; manifold.normal += contactPoint.normal;
} }
} }
@ -272,7 +272,7 @@ void ContactSolver::initializeContactConstraints() {
} }
// If we solve the friction constraints at the center of the contact manifold // If we solve the friction constraints at the center of the contact manifold
if (mIsSolveFrictionAtContactManifoldCenterActive) { if (m_isSolveFrictionAtContactManifoldCenterActive) {
manifold.normal.normalize(); manifold.normal.normalize();
@ -320,12 +320,12 @@ void ContactSolver::initializeContactConstraints() {
void ContactSolver::warmStart() { void ContactSolver::warmStart() {
// Check that warm starting is active // Check that warm starting is active
if (!mIsWarmStartingActive) return; if (!m_isWarmStartingActive) return;
// For each constraint // For each constraint
for (uint32_t c=0; c<m_numberContactManifolds; c++) { for (uint32_t c=0; c<m_numberContactManifolds; c++) {
ContactManifoldSolver& contactManifold = mContactConstraints[c]; ContactManifoldSolver& contactManifold = m_contactConstraints[c];
bool atLeastOneRestingContactPoint = false; bool atLeastOneRestingContactPoint = false;
@ -348,7 +348,7 @@ void ContactSolver::warmStart() {
applyImpulse(impulsePenetration, contactManifold); applyImpulse(impulsePenetration, contactManifold);
// If we do not solve the friction constraints at the center of the contact manifold // If we do not solve the friction constraints at the center of the contact manifold
if (!mIsSolveFrictionAtContactManifoldCenterActive) { if (!m_isSolveFrictionAtContactManifoldCenterActive) {
// Project the old friction impulses (with old friction vectors) int32_to // Project the old friction impulses (with old friction vectors) int32_to
// the new friction vectors to get the new friction impulses // the new friction vectors to get the new friction impulses
@ -404,7 +404,7 @@ void ContactSolver::warmStart() {
// If we solve the friction constraints at the center of the contact manifold and there is // If we solve the friction constraints at the center of the contact manifold and there is
// at least one resting contact point in the contact manifold // at least one resting contact point in the contact manifold
if (mIsSolveFrictionAtContactManifoldCenterActive && atLeastOneRestingContactPoint) { if (m_isSolveFrictionAtContactManifoldCenterActive && atLeastOneRestingContactPoint) {
// Project the old friction impulses (with old friction vectors) int32_to the new friction // Project the old friction impulses (with old friction vectors) int32_to the new friction
// vectors to get the new friction impulses // vectors to get the new friction impulses
@ -497,15 +497,15 @@ void ContactSolver::solve() {
// For each contact manifold // For each contact manifold
for (uint32_t c=0; c<m_numberContactManifolds; c++) { for (uint32_t c=0; c<m_numberContactManifolds; c++) {
ContactManifoldSolver& contactManifold = mContactConstraints[c]; ContactManifoldSolver& contactManifold = m_contactConstraints[c];
float sumPenetrationImpulse = 0.0; float sumPenetrationImpulse = 0.0;
// Get the constrained velocities // Get the constrained velocities
const vec3& v1 = mLinearVelocities[contactManifold.indexBody1]; const vec3& v1 = m_linearVelocities[contactManifold.indexBody1];
const vec3& w1 = mAngularVelocities[contactManifold.indexBody1]; const vec3& w1 = m_angularVelocities[contactManifold.indexBody1];
const vec3& v2 = mLinearVelocities[contactManifold.indexBody2]; const vec3& v2 = m_linearVelocities[contactManifold.indexBody2];
const vec3& w2 = mAngularVelocities[contactManifold.indexBody2]; const vec3& w2 = m_angularVelocities[contactManifold.indexBody2];
for (uint32_t i=0; i<contactManifold.nbContacts; i++) { for (uint32_t i=0; i<contactManifold.nbContacts; i++) {
@ -519,14 +519,14 @@ void ContactSolver::solve() {
float Jv = deltaVDotN; float Jv = deltaVDotN;
// Compute the bias "b" of the constraint // Compute the bias "b" of the constraint
float beta = mIsSplitImpulseActive ? BETA_SPLIT_IMPULSE : BETA; float beta = m_isSplitImpulseActive ? BETA_SPLIT_IMPULSE : BETA;
float biasPenetrationDepth = 0.0; float biasPenetrationDepth = 0.0;
if (contactPoint.penetrationDepth > SLOP) biasPenetrationDepth = -(beta/m_timeStep) * if (contactPoint.penetrationDepth > SLOP) biasPenetrationDepth = -(beta/m_timeStep) *
max(0.0f, float(contactPoint.penetrationDepth - SLOP)); max(0.0f, float(contactPoint.penetrationDepth - SLOP));
float b = biasPenetrationDepth + contactPoint.restitutionBias; float b = biasPenetrationDepth + contactPoint.restitutionBias;
// Compute the Lagrange multiplier lambda // Compute the Lagrange multiplier lambda
if (mIsSplitImpulseActive) { if (m_isSplitImpulseActive) {
deltaLambda = - (Jv + contactPoint.restitutionBias) * deltaLambda = - (Jv + contactPoint.restitutionBias) *
contactPoint.inversePenetrationMass; contactPoint.inversePenetrationMass;
} }
@ -548,7 +548,7 @@ void ContactSolver::solve() {
sumPenetrationImpulse += contactPoint.penetrationImpulse; sumPenetrationImpulse += contactPoint.penetrationImpulse;
// If the split impulse position correction is active // If the split impulse position correction is active
if (mIsSplitImpulseActive) { if (m_isSplitImpulseActive) {
// Split impulse (position correction) // Split impulse (position correction)
const vec3& v1Split = m_splitLinearVelocities[contactManifold.indexBody1]; const vec3& v1Split = m_splitLinearVelocities[contactManifold.indexBody1];
@ -574,7 +574,7 @@ void ContactSolver::solve() {
} }
// If we do not solve the friction constraints at the center of the contact manifold // If we do not solve the friction constraints at the center of the contact manifold
if (!mIsSolveFrictionAtContactManifoldCenterActive) { if (!m_isSolveFrictionAtContactManifoldCenterActive) {
// --------- Friction 1 --------- // // --------- Friction 1 --------- //
@ -650,7 +650,7 @@ void ContactSolver::solve() {
} }
// If we solve the friction constraints at the center of the contact manifold // If we solve the friction constraints at the center of the contact manifold
if (mIsSolveFrictionAtContactManifoldCenterActive) { if (m_isSolveFrictionAtContactManifoldCenterActive) {
// ------ First friction constraint at the center of the contact manifol ------ // // ------ First friction constraint at the center of the contact manifol ------ //
@ -768,7 +768,7 @@ void ContactSolver::storeImpulses() {
// For each contact manifold // For each contact manifold
for (uint32_t c=0; c<m_numberContactManifolds; c++) { for (uint32_t c=0; c<m_numberContactManifolds; c++) {
ContactManifoldSolver& manifold = mContactConstraints[c]; ContactManifoldSolver& manifold = m_contactConstraints[c];
for (uint32_t i=0; i<manifold.nbContacts; i++) { for (uint32_t i=0; i<manifold.nbContacts; i++) {
@ -797,15 +797,15 @@ void ContactSolver::applyImpulse(const Impulse& impulse,
const ContactManifoldSolver& manifold) { const ContactManifoldSolver& manifold) {
// Update the velocities of the body 1 by applying the impulse P // Update the velocities of the body 1 by applying the impulse P
mLinearVelocities[manifold.indexBody1] += manifold.massInverseBody1 * m_linearVelocities[manifold.indexBody1] += manifold.massInverseBody1 *
impulse.linearImpulseBody1; impulse.linearImpulseBody1;
mAngularVelocities[manifold.indexBody1] += manifold.inverseInertiaTensorBody1 * m_angularVelocities[manifold.indexBody1] += manifold.inverseInertiaTensorBody1 *
impulse.angularImpulseBody1; impulse.angularImpulseBody1;
// Update the velocities of the body 1 by applying the impulse P // Update the velocities of the body 1 by applying the impulse P
mLinearVelocities[manifold.indexBody2] += manifold.massInverseBody2 * m_linearVelocities[manifold.indexBody2] += manifold.massInverseBody2 *
impulse.linearImpulseBody2; impulse.linearImpulseBody2;
mAngularVelocities[manifold.indexBody2] += manifold.inverseInertiaTensorBody2 * m_angularVelocities[manifold.indexBody2] += manifold.inverseInertiaTensorBody2 *
impulse.angularImpulseBody2; impulse.angularImpulseBody2;
} }
@ -889,8 +889,8 @@ void ContactSolver::computeFrictionVectors(const vec3& deltaVelocity,
// Clean up the constraint solver // Clean up the constraint solver
void ContactSolver::cleanup() { void ContactSolver::cleanup() {
if (mContactConstraints != nullptr) { if (m_contactConstraints != nullptr) {
delete[] mContactConstraints; delete[] m_contactConstraints;
mContactConstraints = nullptr; m_contactConstraints = nullptr;
} }
} }

View File

@ -5,7 +5,6 @@
*/ */
#pragma once #pragma once
// Libraries
#include <ephysics/constraint/ContactPoint.hpp> #include <ephysics/constraint/ContactPoint.hpp>
#include <ephysics/configuration.hpp> #include <ephysics/configuration.hpp>
#include <ephysics/constraint/Joint.hpp> #include <ephysics/constraint/Joint.hpp>
@ -15,13 +14,9 @@
#include <map> #include <map>
#include <set> #include <set>
/// ReactPhysics3D namespace
namespace ephysics { namespace ephysics {
// Class Contact Solver
/** /**
* This class represents the contact solver that is used to solve rigid bodies contacts. * @brief This class represents the contact solver that is used to solve rigid bodies contacts.
* The constraint solver is based on the "Sequential Impulse" technique described by * The constraint solver is based on the "Sequential Impulse" technique described by
* Erin Catto in his GDC slides (http://code.google.com/p/box2d/downloads/list). * Erin Catto in his GDC slides (http://code.google.com/p/box2d/downloads/list).
* *
@ -89,342 +84,155 @@ namespace ephysics {
* contact manifold center. * contact manifold center.
*/ */
class ContactSolver { class ContactSolver {
private: private:
// Structure ContactPointSolver
/** /**
* Contact solver int32_ternal data structure that to store all the * Contact solver int32_ternal data structure that to store all the
* information relative to a contact point * information relative to a contact point
*/ */
struct ContactPointSolver { struct ContactPointSolver {
float penetrationImpulse; //!< Accumulated normal impulse
/// Accumulated normal impulse float friction1Impulse; //!< Accumulated impulse in the 1st friction direction
float penetrationImpulse; float friction2Impulse; //!< Accumulated impulse in the 2nd friction direction
float penetrationSplitImpulse; //!< Accumulated split impulse for penetration correction
/// Accumulated impulse in the 1st friction direction vec3 rollingResistanceImpulse; //!< Accumulated rolling resistance impulse
float friction1Impulse; vec3 normal; //!< Normal vector of the contact
vec3 frictionVector1; //!< First friction vector in the tangent plane
/// Accumulated impulse in the 2nd friction direction vec3 frictionvec2; //!< Second friction vector in the tangent plane
float friction2Impulse; vec3 oldFrictionVector1; //!< Old first friction vector in the tangent plane
vec3 oldFrictionvec2; //!< Old second friction vector in the tangent plane
/// Accumulated split impulse for penetration correction vec3 r1; //!< Vector from the body 1 center to the contact point
float penetrationSplitImpulse; vec3 r2; //!< Vector from the body 2 center to the contact point
vec3 r1CrossT1; //!< Cross product of r1 with 1st friction vector
/// Accumulated rolling resistance impulse vec3 r1CrossT2; //!< Cross product of r1 with 2nd friction vector
vec3 rollingResistanceImpulse; vec3 r2CrossT1; //!< Cross product of r2 with 1st friction vector
vec3 r2CrossT2; //!< Cross product of r2 with 2nd friction vector
/// Normal vector of the contact vec3 r1CrossN; //!< Cross product of r1 with the contact normal
vec3 normal; vec3 r2CrossN; //!< Cross product of r2 with the contact normal
float penetrationDepth; //!< Penetration depth
/// First friction vector in the tangent plane float restitutionBias; //!< Velocity restitution bias
vec3 frictionVector1; float inversePenetrationMass; //!< Inverse of the matrix K for the penenetration
float inverseFriction1Mass; //!< Inverse of the matrix K for the 1st friction
/// Second friction vector in the tangent plane float inverseFriction2Mass; //!< Inverse of the matrix K for the 2nd friction
vec3 frictionvec2; bool isRestingContact; //!< True if the contact was existing last time step
ContactPoint* externalContact; //!< Pointer to the external contact
/// Old first friction vector in the tangent plane
vec3 oldFrictionVector1;
/// Old second friction vector in the tangent plane
vec3 oldFrictionvec2;
/// Vector from the body 1 center to the contact point
vec3 r1;
/// Vector from the body 2 center to the contact point
vec3 r2;
/// Cross product of r1 with 1st friction vector
vec3 r1CrossT1;
/// Cross product of r1 with 2nd friction vector
vec3 r1CrossT2;
/// Cross product of r2 with 1st friction vector
vec3 r2CrossT1;
/// Cross product of r2 with 2nd friction vector
vec3 r2CrossT2;
/// Cross product of r1 with the contact normal
vec3 r1CrossN;
/// Cross product of r2 with the contact normal
vec3 r2CrossN;
/// Penetration depth
float penetrationDepth;
/// Velocity restitution bias
float restitutionBias;
/// Inverse of the matrix K for the penenetration
float inversePenetrationMass;
/// Inverse of the matrix K for the 1st friction
float inverseFriction1Mass;
/// Inverse of the matrix K for the 2nd friction
float inverseFriction2Mass;
/// True if the contact was existing last time step
bool isRestingContact;
/// Pointer to the external contact
ContactPoint* externalContact;
}; };
// Structure ContactManifoldSolver
/** /**
* Contact solver int32_ternal data structure to store all the * @brief Contact solver int32_ternal data structure to store all the information relative to a contact manifold.
* information relative to a contact manifold.
*/ */
struct ContactManifoldSolver { struct ContactManifoldSolver {
uint32_t indexBody1; //!< Index of body 1 in the constraint solver
/// Index of body 1 in the constraint solver uint32_t indexBody2; //!< Index of body 2 in the constraint solver
uint32_t indexBody1; float massInverseBody1; //!< Inverse of the mass of body 1
float massInverseBody2; //!< Inverse of the mass of body 2
/// Index of body 2 in the constraint solver etk::Matrix3x3 inverseInertiaTensorBody1; //!< Inverse inertia tensor of body 1
uint32_t indexBody2; etk::Matrix3x3 inverseInertiaTensorBody2; //!< Inverse inertia tensor of body 2
ContactPointSolver contacts[MAX_CONTACT_POINTS_IN_MANIFOLD]; //!< Contact point constraints
/// Inverse of the mass of body 1 uint32_t nbContacts; //!< Number of contact points
float massInverseBody1; bool isBody1DynamicType; //!< True if the body 1 is of type dynamic
bool isBody2DynamicType; //!< True if the body 2 is of type dynamic
// Inverse of the mass of body 2 float restitutionFactor; //!< Mix of the restitution factor for two bodies
float massInverseBody2; float frictionCoefficient; //!< Mix friction coefficient for the two bodies
float rollingResistanceFactor; //!< Rolling resistance factor between the two bodies
/// Inverse inertia tensor of body 1 ContactManifold* externalContactManifold; //!< Pointer to the external contact manifold
etk::Matrix3x3 inverseInertiaTensorBody1;
/// Inverse inertia tensor of body 2
etk::Matrix3x3 inverseInertiaTensorBody2;
/// Contact point constraints
ContactPointSolver contacts[MAX_CONTACT_POINTS_IN_MANIFOLD];
/// Number of contact points
uint32_t nbContacts;
/// True if the body 1 is of type dynamic
bool isBody1DynamicType;
/// True if the body 2 is of type dynamic
bool isBody2DynamicType;
/// Mix of the restitution factor for two bodies
float restitutionFactor;
/// Mix friction coefficient for the two bodies
float frictionCoefficient;
/// Rolling resistance factor between the two bodies
float rollingResistanceFactor;
/// Pointer to the external contact manifold
ContactManifold* externalContactManifold;
// - Variables used when friction constraints are apply at the center of the manifold-// // - Variables used when friction constraints are apply at the center of the manifold-//
vec3 normal; //!< Average normal vector of the contact manifold
/// Average normal vector of the contact manifold vec3 frictionPointBody1; //!< Point on body 1 where to apply the friction constraints
vec3 normal; vec3 frictionPointBody2; //!< Point on body 2 where to apply the friction constraints
vec3 r1Friction; //!< R1 vector for the friction constraints
/// Point on body 1 where to apply the friction constraints vec3 r2Friction; //!< R2 vector for the friction constraints
vec3 frictionPointBody1; vec3 r1CrossT1; //!< Cross product of r1 with 1st friction vector
vec3 r1CrossT2; //!< Cross product of r1 with 2nd friction vector
/// Point on body 2 where to apply the friction constraints vec3 r2CrossT1; //!< Cross product of r2 with 1st friction vector
vec3 frictionPointBody2; vec3 r2CrossT2; //!< Cross product of r2 with 2nd friction vector
float inverseFriction1Mass; //!< Matrix K for the first friction constraint
/// R1 vector for the friction constraints float inverseFriction2Mass; //!< Matrix K for the second friction constraint
vec3 r1Friction; float inverseTwistFrictionMass; //!< Matrix K for the twist friction constraint
etk::Matrix3x3 inverseRollingResistance; //!< Matrix K for the rolling resistance constraint
/// R2 vector for the friction constraints vec3 frictionVector1; //!< First friction direction at contact manifold center
vec3 r2Friction; vec3 frictionvec2; //!< Second friction direction at contact manifold center
vec3 oldFrictionVector1; //!< Old 1st friction direction at contact manifold center
/// Cross product of r1 with 1st friction vector vec3 oldFrictionvec2; //!< Old 2nd friction direction at contact manifold center
vec3 r1CrossT1; float friction1Impulse; //!< First friction direction impulse at manifold center
float friction2Impulse; //!< Second friction direction impulse at manifold center
/// Cross product of r1 with 2nd friction vector float frictionTwistImpulse; //!< Twist friction impulse at contact manifold center
vec3 r1CrossT2; vec3 rollingResistanceImpulse; //!< Rolling resistance impulse
/// Cross product of r2 with 1st friction vector
vec3 r2CrossT1;
/// Cross product of r2 with 2nd friction vector
vec3 r2CrossT2;
/// Matrix K for the first friction constraint
float inverseFriction1Mass;
/// Matrix K for the second friction constraint
float inverseFriction2Mass;
/// Matrix K for the twist friction constraint
float inverseTwistFrictionMass;
/// Matrix K for the rolling resistance constraint
etk::Matrix3x3 inverseRollingResistance;
/// First friction direction at contact manifold center
vec3 frictionVector1;
/// Second friction direction at contact manifold center
vec3 frictionvec2;
/// Old 1st friction direction at contact manifold center
vec3 oldFrictionVector1;
/// Old 2nd friction direction at contact manifold center
vec3 oldFrictionvec2;
/// First friction direction impulse at manifold center
float friction1Impulse;
/// Second friction direction impulse at manifold center
float friction2Impulse;
/// Twist friction impulse at contact manifold center
float frictionTwistImpulse;
/// Rolling resistance impulse
vec3 rollingResistanceImpulse;
}; };
static const float BETA; //!< Beta value for the penetration depth position correction without split impulses
// -------------------- Constants --------------------- // static const float BETA_SPLIT_IMPULSE; //!< Beta value for the penetration depth position correction with split impulses
static const float SLOP; //!< Slop distance (allowed penetration distance between bodies)
/// Beta value for the penetration depth position correction without split impulses vec3* m_splitLinearVelocities; //!< Split linear velocities for the position contact solver (split impulse)
static const float BETA; vec3* m_splitAngularVelocities; //!< Split angular velocities for the position contact solver (split impulse)
float m_timeStep; //!< Current time step
/// Beta value for the penetration depth position correction with split impulses ContactManifoldSolver* m_contactConstraints; //!< Contact constraints
static const float BETA_SPLIT_IMPULSE; uint32_t m_numberContactManifolds; //!< Number of contact constraints
vec3* m_linearVelocities; //!< Array of linear velocities
/// Slop distance (allowed penetration distance between bodies) vec3* m_angularVelocities; //!< Array of angular velocities
static const float SLOP; const std::map<RigidBody*, uint32_t>& m_mapBodyToConstrainedVelocityIndex; //!< Reference to the map of rigid body to their index in the constrained velocities array
bool m_isWarmStartingActive; //!< True if the warm starting of the solver is active
// -------------------- Attributes -------------------- // bool m_isSplitImpulseActive; //!< True if the split impulse position correction is active
bool m_isSolveFrictionAtContactManifoldCenterActive; //!< True if we solve 3 friction constraints at the contact manifold center only instead of 2 friction constraints at each contact point
/// Split linear velocities for the position contact solver (split impulse)
vec3* m_splitLinearVelocities;
/// Split angular velocities for the position contact solver (split impulse)
vec3* m_splitAngularVelocities;
/// Current time step
float m_timeStep;
/// Contact constraints
ContactManifoldSolver* mContactConstraints;
/// Number of contact constraints
uint32_t m_numberContactManifolds;
/// Array of linear velocities
vec3* mLinearVelocities;
/// Array of angular velocities
vec3* mAngularVelocities;
/// Reference to the map of rigid body to their index in the constrained velocities array
const std::map<RigidBody*, uint32_t>& m_mapBodyToConstrainedVelocityIndex;
/// True if the warm starting of the solver is active
bool mIsWarmStartingActive;
/// True if the split impulse position correction is active
bool mIsSplitImpulseActive;
/// True if we solve 3 friction constraints at the contact manifold center only
/// instead of 2 friction constraints at each contact point
bool mIsSolveFrictionAtContactManifoldCenterActive;
// -------------------- Methods -------------------- //
/// Initialize the contact constraints before solving the system /// Initialize the contact constraints before solving the system
void initializeContactConstraints(); void initializeContactConstraints();
/// Apply an impulse to the two bodies of a constraint /// Apply an impulse to the two bodies of a constraint
void applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold); void applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold);
/// Apply an impulse to the two bodies of a constraint /// Apply an impulse to the two bodies of a constraint
void applySplitImpulse(const Impulse& impulse, void applySplitImpulse(const Impulse& impulse,
const ContactManifoldSolver& manifold); const ContactManifoldSolver& manifold);
/// Compute the collision restitution factor from the restitution factor of each body /// Compute the collision restitution factor from the restitution factor of each body
float computeMixedRestitutionFactor(RigidBody *body1, float computeMixedRestitutionFactor(RigidBody *body1,
RigidBody *body2) const; RigidBody *body2) const;
/// Compute the mixed friction coefficient from the friction coefficient of each body /// Compute the mixed friction coefficient from the friction coefficient of each body
float computeMixedFrictionCoefficient(RigidBody* body1, float computeMixedFrictionCoefficient(RigidBody* body1,
RigidBody* body2) const; RigidBody* body2) const;
/// Compute th mixed rolling resistance factor between two bodies /// Compute th mixed rolling resistance factor between two bodies
float computeMixedRollingResistance(RigidBody* body1, RigidBody* body2) const; float computeMixedRollingResistance(RigidBody* body1, RigidBody* body2) const;
/// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction /// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction
/// plane for a contact point. The two vectors have to be /// plane for a contact point. The two vectors have to be
/// such that : t1 x t2 = contactNormal. /// such that : t1 x t2 = contactNormal.
void computeFrictionVectors(const vec3& deltaVelocity, void computeFrictionVectors(const vec3& deltaVelocity,
ContactPointSolver &contactPoint) const; ContactPointSolver &contactPoint) const;
/// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction /// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction
/// plane for a contact manifold. The two vectors have to be /// plane for a contact manifold. The two vectors have to be
/// such that : t1 x t2 = contactNormal. /// such that : t1 x t2 = contactNormal.
void computeFrictionVectors(const vec3& deltaVelocity, void computeFrictionVectors(const vec3& deltaVelocity,
ContactManifoldSolver& contactPoint) const; ContactManifoldSolver& contactPoint) const;
/// Compute a penetration constraint impulse /// Compute a penetration constraint impulse
const Impulse computePenetrationImpulse(float deltaLambda, const Impulse computePenetrationImpulse(float deltaLambda,
const ContactPointSolver& contactPoint) const; const ContactPointSolver& contactPoint) const;
/// Compute the first friction constraint impulse /// Compute the first friction constraint impulse
const Impulse computeFriction1Impulse(float deltaLambda, const Impulse computeFriction1Impulse(float deltaLambda,
const ContactPointSolver& contactPoint) const; const ContactPointSolver& contactPoint) const;
/// Compute the second friction constraint impulse /// Compute the second friction constraint impulse
const Impulse computeFriction2Impulse(float deltaLambda, const Impulse computeFriction2Impulse(float deltaLambda,
const ContactPointSolver& contactPoint) const; const ContactPointSolver& contactPoint) const;
public: public:
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
ContactSolver(const std::map<RigidBody*, uint32_t>& mapBodyToVelocityIndex); ContactSolver(const std::map<RigidBody*, uint32_t>& mapBodyToVelocityIndex);
/// Destructor /// Destructor
virtual ~ContactSolver(); virtual ~ContactSolver();
/// Initialize the constraint solver for a given island /// Initialize the constraint solver for a given island
void initializeForIsland(float dt, Island* island); void initializeForIsland(float dt, Island* island);
/// Set the split velocities arrays /// Set the split velocities arrays
void setSplitVelocitiesArrays(vec3* splitLinearVelocities, void setSplitVelocitiesArrays(vec3* splitLinearVelocities,
vec3* splitAngularVelocities); vec3* splitAngularVelocities);
/// Set the constrained velocities arrays /// Set the constrained velocities arrays
void setConstrainedVelocitiesArrays(vec3* constrainedLinearVelocities, void setConstrainedVelocitiesArrays(vec3* constrainedLinearVelocities,
vec3* constrainedAngularVelocities); vec3* constrainedAngularVelocities);
/// Warm start the solver. /// Warm start the solver.
void warmStart(); void warmStart();
/// Store the computed impulses to use them to /// Store the computed impulses to use them to
/// warm start the solver at the next iteration /// warm start the solver at the next iteration
void storeImpulses(); void storeImpulses();
/// Solve the contacts /// Solve the contacts
void solve(); void solve();
/// Return true if the split impulses position correction technique is used for contacts /// Return true if the split impulses position correction technique is used for contacts
bool isSplitImpulseActive() const; bool isSplitImpulseActive() const;
/// Activate or Deactivate the split impulses for contacts /// Activate or Deactivate the split impulses for contacts
void setIsSplitImpulseActive(bool isActive); void setIsSplitImpulseActive(bool isActive);
/// Activate or deactivate the solving of friction constraints at the center of /// Activate or deactivate the solving of friction constraints at the center of
/// the contact manifold instead of solving them at each contact point /// the contact manifold instead of solving them at each contact point
void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive); void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive);
/// Clean up the constraint solver /// Clean up the constraint solver
void cleanup(); void cleanup();
}; };
@ -443,24 +251,24 @@ inline void ContactSolver::setConstrainedVelocitiesArrays(vec3* constrainedLinea
vec3* constrainedAngularVelocities) { vec3* constrainedAngularVelocities) {
assert(constrainedLinearVelocities != NULL); assert(constrainedLinearVelocities != NULL);
assert(constrainedAngularVelocities != NULL); assert(constrainedAngularVelocities != NULL);
mLinearVelocities = constrainedLinearVelocities; m_linearVelocities = constrainedLinearVelocities;
mAngularVelocities = constrainedAngularVelocities; m_angularVelocities = constrainedAngularVelocities;
} }
// Return true if the split impulses position correction technique is used for contacts // Return true if the split impulses position correction technique is used for contacts
inline bool ContactSolver::isSplitImpulseActive() const { inline bool ContactSolver::isSplitImpulseActive() const {
return mIsSplitImpulseActive; return m_isSplitImpulseActive;
} }
// Activate or Deactivate the split impulses for contacts // Activate or Deactivate the split impulses for contacts
inline void ContactSolver::setIsSplitImpulseActive(bool isActive) { inline void ContactSolver::setIsSplitImpulseActive(bool isActive) {
mIsSplitImpulseActive = isActive; m_isSplitImpulseActive = isActive;
} }
// Activate or deactivate the solving of friction constraints at the center of // Activate or deactivate the solving of friction constraints at the center of
// the contact manifold instead of solving them at each contact point // the contact manifold instead of solving them at each contact point
inline void ContactSolver::setIsSolveFrictionAtContactManifoldCenterActive(bool isActive) { inline void ContactSolver::setIsSolveFrictionAtContactManifoldCenterActive(bool isActive) {
mIsSolveFrictionAtContactManifoldCenterActive = isActive; m_isSolveFrictionAtContactManifoldCenterActive = isActive;
} }
// Compute the collision restitution factor from the restitution factor of each body // Compute the collision restitution factor from the restitution factor of each body

View File

@ -5,7 +5,6 @@
*/ */
#pragma once #pragma once
// Libraries
#include <ephysics/engine/CollisionWorld.hpp> #include <ephysics/engine/CollisionWorld.hpp>
#include <ephysics/collision/CollisionDetection.hpp> #include <ephysics/collision/CollisionDetection.hpp>
#include <ephysics/engine/ContactSolver.hpp> #include <ephysics/engine/ContactSolver.hpp>
@ -14,273 +13,155 @@
#include <ephysics/engine/Island.hpp> #include <ephysics/engine/Island.hpp>
#include <ephysics/configuration.hpp> #include <ephysics/configuration.hpp>
/// Namespace ReactPhysics3D
namespace ephysics { namespace ephysics {
// Class DynamicsWorld
/** /**
* This class represents a dynamics world. This class inherits from * @brief This class represents a dynamics world. This class inherits from
* the CollisionWorld class. In a dynamics world, bodies can collide * the CollisionWorld class. In a dynamics world, bodies can collide
* and their movements are simulated using the laws of physics. * and their movements are simulated using the laws of physics.
*/ */
class DynamicsWorld : public CollisionWorld { class DynamicsWorld : public CollisionWorld {
protected : protected :
ContactSolver m_contactSolver; //!< Contact solver
// -------------------- Attributes -------------------- // ConstraintSolver m_constraintSolver; //!< Constraint solver
uint32_t m_nbVelocitySolverIterations; //!< Number of iterations for the velocity solver of the Sequential Impulses technique
/// Contact solver uint32_t m_nbPositionSolverIterations; //!< Number of iterations for the position solver of the Sequential Impulses technique
ContactSolver m_contactSolver; bool m_isSleepingEnabled; //!< True if the spleeping technique for inactive bodies is enabled
std::set<RigidBody*> m_rigidBodies; //!< All the rigid bodies of the physics world
/// Constraint solver std::set<Joint*> m_joints; //!< All the joints of the world
ConstraintSolver m_constraintSolver; vec3 m_gravity; //!< Gravity vector of the world
float m_timeStep; //!< Current frame time step (in seconds)
/// Number of iterations for the velocity solver of the Sequential Impulses technique bool m_isGravityEnabled; //!< True if the gravity force is on
uint32_t m_nbVelocitySolverIterations; vec3* m_constrainedLinearVelocities; //!< Array of constrained linear velocities (state of the linear velocities after solving the constraints)
vec3* m_constrainedAngularVelocities; //!< Array of constrained angular velocities (state of the angular velocities after solving the constraints)
/// Number of iterations for the position solver of the Sequential Impulses technique vec3* m_splitLinearVelocities; //!< Split linear velocities for the position contact solver (split impulse)
uint32_t m_nbPositionSolverIterations; vec3* m_splitAngularVelocities; //!< Split angular velocities for the position contact solver (split impulse)
vec3* m_constrainedPositions; //!< Array of constrained rigid bodies position (for position error correction)
/// True if the spleeping technique for inactive bodies is enabled etk::Quaternion* m_constrainedOrientations; //!< Array of constrained rigid bodies orientation (for position error correction)
bool m_isSleepingEnabled; std::map<RigidBody*, uint32_t> m_mapBodyToConstrainedVelocityIndex; //!< Map body to their index in the constrained velocities array
uint32_t m_numberIslands; //!< Number of islands in the world
/// All the rigid bodies of the physics world uint32_t m_numberIslandsCapacity; //!< Current allocated capacity for the islands
std::set<RigidBody*> m_rigidBodies; Island** m_islands; //!< Array with all the islands of awaken bodies
uint32_t m_numberBodiesCapacity; //!< Current allocated capacity for the bodies
/// All the joints of the world float m_sleepLinearVelocity; //!< Sleep linear velocity threshold
std::set<Joint*> m_joints; float m_sleepAngularVelocity; //!< Sleep angular velocity threshold
float m_timeBeforeSleep; //!< Time (in seconds) before a body is put to sleep if its velocity becomes smaller than the sleep velocity.
/// Gravity vector of the world
vec3 m_gravity;
/// Current frame time step (in seconds)
float m_timeStep;
/// True if the gravity force is on
bool m_isGravityEnabled;
/// Array of constrained linear velocities (state of the linear velocities
/// after solving the constraints)
vec3* m_constrainedLinearVelocities;
/// Array of constrained angular velocities (state of the angular velocities
/// after solving the constraints)
vec3* m_constrainedAngularVelocities;
/// Split linear velocities for the position contact solver (split impulse)
vec3* m_splitLinearVelocities;
/// Split angular velocities for the position contact solver (split impulse)
vec3* m_splitAngularVelocities;
/// Array of constrained rigid bodies position (for position error correction)
vec3* m_constrainedPositions;
/// Array of constrained rigid bodies orientation (for position error correction)
etk::Quaternion* m_constrainedOrientations;
/// Map body to their index in the constrained velocities array
std::map<RigidBody*, uint32_t> m_mapBodyToConstrainedVelocityIndex;
/// Number of islands in the world
uint32_t m_numberIslands;
/// Current allocated capacity for the islands
uint32_t m_numberIslandsCapacity;
/// Array with all the islands of awaken bodies
Island** m_islands;
/// Current allocated capacity for the bodies
uint32_t m_numberBodiesCapacity;
/// Sleep linear velocity threshold
float m_sleepLinearVelocity;
/// Sleep angular velocity threshold
float m_sleepAngularVelocity;
/// Time (in seconds) before a body is put to sleep if its velocity
/// becomes smaller than the sleep velocity.
float m_timeBeforeSleep;
// -------------------- Methods -------------------- //
/// Private copy-constructor /// Private copy-constructor
DynamicsWorld(const DynamicsWorld& world); DynamicsWorld(const DynamicsWorld& world);
/// Private assignment operator /// Private assignment operator
DynamicsWorld& operator=(const DynamicsWorld& world); DynamicsWorld& operator=(const DynamicsWorld& world);
/// Integrate the positions and orientations of rigid bodies. /// Integrate the positions and orientations of rigid bodies.
void int32_tegrateRigidBodiesPositions(); void int32_tegrateRigidBodiesPositions();
/// Update the AABBs of the bodies /// Update the AABBs of the bodies
void updateRigidBodiesAABB(); void updateRigidBodiesAABB();
/// Reset the external force and torque applied to the bodies /// Reset the external force and torque applied to the bodies
void resetBodiesForceAndTorque(); void resetBodiesForceAndTorque();
/// Update the position and orientation of a body /// Update the position and orientation of a body
void updatePositionAndOrientationOfBody(RigidBody* body, vec3 newLinVelocity, void updatePositionAndOrientationOfBody(RigidBody* body, vec3 newLinVelocity,
vec3 newAngVelocity); vec3 newAngVelocity);
/// Compute and set the int32_terpolation factor to all bodies /// Compute and set the int32_terpolation factor to all bodies
void setInterpolationFactorToAllBodies(); void setInterpolationFactorToAllBodies();
/// Initialize the bodies velocities arrays for the next simulation step. /// Initialize the bodies velocities arrays for the next simulation step.
void initVelocityArrays(); void initVelocityArrays();
/// Integrate the velocities of rigid bodies. /// Integrate the velocities of rigid bodies.
void int32_tegrateRigidBodiesVelocities(); void int32_tegrateRigidBodiesVelocities();
/// Solve the contacts and constraints /// Solve the contacts and constraints
void solveContactsAndConstraints(); void solveContactsAndConstraints();
/// Solve the position error correction of the constraints /// Solve the position error correction of the constraints
void solvePositionCorrection(); void solvePositionCorrection();
/// Cleanup the constrained velocities array at each step /// Cleanup the constrained velocities array at each step
void cleanupConstrainedVelocitiesArray(); void cleanupConstrainedVelocitiesArray();
/// Compute the islands of awake bodies. /// Compute the islands of awake bodies.
void computeIslands(); void computeIslands();
/// Update the postion/orientation of the bodies /// Update the postion/orientation of the bodies
void updateBodiesState(); void updateBodiesState();
/// Put bodies to sleep if needed. /// Put bodies to sleep if needed.
void updateSleepingBodies(); void updateSleepingBodies();
/// Add the joint to the list of joints of the two bodies involved in the joint /// Add the joint to the list of joints of the two bodies involved in the joint
void addJointToBody(Joint* joint); void addJointToBody(Joint* joint);
public : public :
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
DynamicsWorld(const vec3& m_gravity); DynamicsWorld(const vec3& m_gravity);
/// Destructor /// Destructor
virtual ~DynamicsWorld(); virtual ~DynamicsWorld();
/// Update the physics simulation /// Update the physics simulation
void update(float timeStep); void update(float timeStep);
/// Get the number of iterations for the velocity constraint solver /// Get the number of iterations for the velocity constraint solver
uint32_t getNbIterationsVelocitySolver() const; uint32_t getNbIterationsVelocitySolver() const;
/// Set the number of iterations for the velocity constraint solver /// Set the number of iterations for the velocity constraint solver
void setNbIterationsVelocitySolver(uint32_t nbIterations); void setNbIterationsVelocitySolver(uint32_t nbIterations);
/// Get the number of iterations for the position constraint solver /// Get the number of iterations for the position constraint solver
uint32_t getNbIterationsPositionSolver() const; uint32_t getNbIterationsPositionSolver() const;
/// Set the number of iterations for the position constraint solver /// Set the number of iterations for the position constraint solver
void setNbIterationsPositionSolver(uint32_t nbIterations); void setNbIterationsPositionSolver(uint32_t nbIterations);
/// Set the position correction technique used for contacts /// Set the position correction technique used for contacts
void setContactsPositionCorrectionTechnique(ContactsPositionCorrectionTechnique technique); void setContactsPositionCorrectionTechnique(ContactsPositionCorrectionTechnique technique);
/// Set the position correction technique used for joints /// Set the position correction technique used for joints
void setJointsPositionCorrectionTechnique(JointsPositionCorrectionTechnique technique); void setJointsPositionCorrectionTechnique(JointsPositionCorrectionTechnique technique);
/// Activate or deactivate the solving of friction constraints at the center of /// Activate or deactivate the solving of friction constraints at the center of
/// the contact manifold instead of solving them at each contact point /// the contact manifold instead of solving them at each contact point
void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive); void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive);
/// Create a rigid body int32_to the physics world. /// Create a rigid body int32_to the physics world.
RigidBody* createRigidBody(const etk::Transform3D& transform); RigidBody* createRigidBody(const etk::Transform3D& transform);
/// Destroy a rigid body and all the joints which it belongs /// Destroy a rigid body and all the joints which it belongs
void destroyRigidBody(RigidBody* rigidBody); void destroyRigidBody(RigidBody* rigidBody);
/// Create a joint between two bodies in the world and return a pointer to the new joint /// Create a joint between two bodies in the world and return a pointer to the new joint
Joint* createJoint(const JointInfo& jointInfo); Joint* createJoint(const JointInfo& jointInfo);
/// Destroy a joint /// Destroy a joint
void destroyJoint(Joint* joint); void destroyJoint(Joint* joint);
/// Return the gravity vector of the world /// Return the gravity vector of the world
vec3 getGravity() const; vec3 getGravity() const;
/// Set the gravity vector of the world /// Set the gravity vector of the world
void setGravity(vec3& gravity); void setGravity(vec3& gravity);
/// Return if the gravity is on /// Return if the gravity is on
bool isGravityEnabled() const; bool isGravityEnabled() const;
/// Enable/Disable the gravity /// Enable/Disable the gravity
void setIsGratityEnabled(bool isGravityEnabled); void setIsGratityEnabled(bool isGravityEnabled);
/// Return the number of rigid bodies in the world /// Return the number of rigid bodies in the world
uint32_t getNbRigidBodies() const; uint32_t getNbRigidBodies() const;
/// Return the number of joints in the world /// Return the number of joints in the world
uint32_t getNbJoints() const; uint32_t getNbJoints() const;
/// Return an iterator to the beginning of the rigid bodies of the physics world /// Return an iterator to the beginning of the rigid bodies of the physics world
std::set<RigidBody*>::iterator getRigidBodiesBeginIterator(); std::set<RigidBody*>::iterator getRigidBodiesBeginIterator();
/// Return an iterator to the end of the rigid bodies of the physics world /// Return an iterator to the end of the rigid bodies of the physics world
std::set<RigidBody*>::iterator getRigidBodiesEndIterator(); std::set<RigidBody*>::iterator getRigidBodiesEndIterator();
/// Return true if the sleeping technique is enabled /// Return true if the sleeping technique is enabled
bool isSleepingEnabled() const; bool isSleepingEnabled() const;
/// Enable/Disable the sleeping technique /// Enable/Disable the sleeping technique
void enableSleeping(bool isSleepingEnabled); void enableSleeping(bool isSleepingEnabled);
/// Return the current sleep linear velocity /// Return the current sleep linear velocity
float getSleepLinearVelocity() const; float getSleepLinearVelocity() const;
/// Set the sleep linear velocity. /// Set the sleep linear velocity.
void setSleepLinearVelocity(float sleepLinearVelocity); void setSleepLinearVelocity(float sleepLinearVelocity);
/// Return the current sleep angular velocity /// Return the current sleep angular velocity
float getSleepAngularVelocity() const; float getSleepAngularVelocity() const;
/// Set the sleep angular velocity. /// Set the sleep angular velocity.
void setSleepAngularVelocity(float sleepAngularVelocity); void setSleepAngularVelocity(float sleepAngularVelocity);
/// Return the time a body is required to stay still before sleeping /// Return the time a body is required to stay still before sleeping
float getTimeBeforeSleep() const; float getTimeBeforeSleep() const;
/// Set the time a body is required to stay still before sleeping /// Set the time a body is required to stay still before sleeping
void setTimeBeforeSleep(float timeBeforeSleep); void setTimeBeforeSleep(float timeBeforeSleep);
/// Set an event listener object to receive events callbacks. /// Set an event listener object to receive events callbacks.
void setEventListener(EventListener* eventListener); void setEventListener(EventListener* eventListener);
/// Test and report collisions between a given shape and all the others /// Test and report collisions between a given shape and all the others
/// shapes of the world /// shapes of the world
virtual void testCollision(const ProxyShape* shape, virtual void testCollision(const ProxyShape* shape,
CollisionCallback* callback); CollisionCallback* callback);
/// Test and report collisions between two given shapes /// Test and report collisions between two given shapes
virtual void testCollision(const ProxyShape* shape1, virtual void testCollision(const ProxyShape* shape1,
const ProxyShape* shape2, const ProxyShape* shape2,
CollisionCallback* callback); CollisionCallback* callback);
/// Test and report collisions between a body and all /// Test and report collisions between a body and all
/// the others bodies of the world /// the others bodies of the world
virtual void testCollision(const CollisionBody* body, virtual void testCollision(const CollisionBody* body,
CollisionCallback* callback); CollisionCallback* callback);
/// Test and report collisions between two bodies /// Test and report collisions between two bodies
virtual void testCollision(const CollisionBody* body1, virtual void testCollision(const CollisionBody* body1,
const CollisionBody* body2, const CollisionBody* body2,
CollisionCallback* callback); CollisionCallback* callback);
/// Test and report collisions between all shapes of the world /// Test and report collisions between all shapes of the world
virtual void testCollision(CollisionCallback* callback); virtual void testCollision(CollisionCallback* callback);
/// Return the list of all contacts of the world /// Return the list of all contacts of the world
std::vector<const ContactManifold*> getContactsList() const; std::vector<const ContactManifold*> getContactsList() const;
// -------------------- Friendship -------------------- //
friend class RigidBody; friend class RigidBody;
}; };

View File

@ -5,52 +5,49 @@
*/ */
#pragma once #pragma once
// Libraries
#include <ephysics/constraint/ContactPoint.hpp> #include <ephysics/constraint/ContactPoint.hpp>
namespace ephysics { namespace ephysics {
// Class EventListener
/** /**
* This class can be used to receive event callbacks from the physics engine. * @brief 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 * 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 * 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 DynamicsWorld::setEventListener()
* method. * method.
*/ */
class EventListener { class EventListener {
public : public :
/// Constructor
EventListener() {}
/// Destructor
virtual ~EventListener() {}
/// Called when a new contact point is found between two bodies that were separated before
/** /**
* @brief Generic Constructor
*/
EventListener() {}
/**
* @brief Generic Desstructor take it virtual
*/
virtual ~EventListener() =default;
/**
* @brief Called when a new contact point is found between two bodies that were separated before
* @param contact Information about the contact * @param contact Information about the contact
*/ */
virtual void beginContact(const ContactPointInfo& contact) {}; virtual void beginContact(const ContactPointInfo& contact) {};
/// Called when a new contact point is found between two bodies
/** /**
* @brief Called when a new contact point is found between two bodies
* @param contact Information about the contact * @param contact Information about the contact
*/ */
virtual void newContact(const ContactPointInfo& contact) {} virtual void newContact(const ContactPointInfo& contact) {}
/**
/// Called at the beginning of an int32_ternal tick of the simulation step. * @brief Called at the beginning of an int32_ternal tick of the simulation step.
/// Each time the DynamicsWorld::update() method is called, the physics * Each time the DynamicsWorld::update() method is called, the physics
/// engine will do several int32_ternal simulation steps. This method is * engine will do several int32_ternal simulation steps. This method is
/// called at the beginning of each int32_ternal simulation step. * called at the beginning of each int32_ternal simulation step.
*/
virtual void beginInternalTick() {} virtual void beginInternalTick() {}
/**
/// Called at the end of an int32_ternal tick of the simulation step. * @brief Called at the end of an int32_ternal tick of the simulation step.
/// Each time the DynamicsWorld::update() metho is called, the physics * Each time the DynamicsWorld::update() metho is called, the physics
/// engine will do several int32_ternal simulation steps. This method is * engine will do several int32_ternal simulation steps. This method is
/// called at the end of each int32_ternal simulation step. * called at the end of each int32_ternal simulation step.
*/
virtual void endInternalTick() {} virtual void endInternalTick() {}
}; };
} }

View File

@ -5,60 +5,39 @@
*/ */
#pragma once #pragma once
// Libraries
#include <ephysics/mathematics/mathematics.hpp> #include <ephysics/mathematics/mathematics.hpp>
namespace ephysics { namespace ephysics {
// Structure Impulse
/** /**
* Represents an impulse that we can apply to bodies in the contact or constraint solver. * @brief Represents an impulse that we can apply to bodies in the contact or constraint solver.
*/ */
struct Impulse { class Impulse {
private: private:
// -------------------- Methods -------------------- //
/// Private assignment operator /// Private assignment operator
Impulse& operator=(const Impulse& impulse); Impulse& operator=(const Impulse& _impulse);
public: public:
const vec3 linearImpulseBody1; //!< Linear impulse applied to the first body
// -------------------- Attributes -------------------- // const vec3 angularImpulseBody1; //!< Angular impulse applied to the first body
const vec3 linearImpulseBody2; //!< Linear impulse applied to the second body
/// Linear impulse applied to the first body const vec3 angularImpulseBody2; //!< Angular impulse applied to the second body
const vec3 linearImpulseBody1;
/// Angular impulse applied to the first body
const vec3 angularImpulseBody1;
/// Linear impulse applied to the second body
const vec3 linearImpulseBody2;
/// Angular impulse applied to the second body
const vec3 angularImpulseBody2;
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
Impulse(const vec3& initLinearImpulseBody1, const vec3& initAngularImpulseBody1, Impulse(const vec3& _initLinearImpulseBody1,
const vec3& initLinearImpulseBody2, const vec3& initAngularImpulseBody2) const vec3& _initAngularImpulseBody1,
: linearImpulseBody1(initLinearImpulseBody1), const vec3& _initLinearImpulseBody2,
angularImpulseBody1(initAngularImpulseBody1), const vec3& _initAngularImpulseBody2):
linearImpulseBody2(initLinearImpulseBody2), linearImpulseBody1(_initLinearImpulseBody1),
angularImpulseBody2(initAngularImpulseBody2) { angularImpulseBody1(_initAngularImpulseBody1),
linearImpulseBody2(_initLinearImpulseBody2),
angularImpulseBody2(_initAngularImpulseBody2) {
} }
/// Copy-constructor /// Copy-constructor
Impulse(const Impulse& impulse) Impulse(const Impulse& _impulse):
: linearImpulseBody1(impulse.linearImpulseBody1), linearImpulseBody1(_impulse.linearImpulseBody1),
angularImpulseBody1(impulse.angularImpulseBody1), angularImpulseBody1(_impulse.angularImpulseBody1),
linearImpulseBody2(impulse.linearImpulseBody2), linearImpulseBody2(_impulse.linearImpulseBody2),
angularImpulseBody2(impulse.angularImpulseBody2) { angularImpulseBody2(_impulse.angularImpulseBody2) {
;
} }
}; };
} }

View File

@ -4,7 +4,6 @@
* @license BSD 3 clauses (see license file) * @license BSD 3 clauses (see license file)
*/ */
// Libraries
#include <ephysics/engine/Island.hpp> #include <ephysics/engine/Island.hpp>
using namespace ephysics; using namespace ephysics;

View File

@ -5,103 +5,56 @@
*/ */
#pragma once #pragma once
// Libraries
#include <ephysics/memory/MemoryAllocator.hpp> #include <ephysics/memory/MemoryAllocator.hpp>
#include <ephysics/body/RigidBody.hpp> #include <ephysics/body/RigidBody.hpp>
#include <ephysics/constraint/Joint.hpp> #include <ephysics/constraint/Joint.hpp>
#include <ephysics/collision/ContactManifold.hpp> #include <ephysics/collision/ContactManifold.hpp>
namespace ephysics { namespace ephysics {
// Class Island
/** /**
* An island represent an isolated group of awake bodies that are connected with each other by * @brief An island represent an isolated group of awake bodies that are connected with each other by
* some contraints (contacts or joints). * some contraints (contacts or joints).
*/ */
class Island { class Island {
private: private:
RigidBody** m_bodies; //!< Array with all the bodies of the island
// -------------------- Attributes -------------------- // ContactManifold** m_contactManifolds; //!< Array with all the contact manifolds between bodies of the island
Joint** m_joints; //!< Array with all the joints between bodies of the island
/// Array with all the bodies of the island uint32_t m_numberBodies; //!< Current number of bodies in the island
RigidBody** m_bodies; uint32_t m_numberContactManifolds; //!< Current number of contact manifold in the island
uint32_t m_numberJoints; //!< Current number of joints in the island
/// Array with all the contact manifolds between bodies of the island MemoryAllocator& m_memoryAllocator; //!< Reference to the memory allocator
ContactManifold** m_contactManifolds; size_t m_numberAllocatedBytesBodies; //!< Number of bytes allocated for the bodies array
size_t m_numberAllocatedBytesContactManifolds; //!< Number of bytes allocated for the contact manifolds array
/// Array with all the joints between bodies of the island size_t m_numberAllocatedBytesJoints; //!< Number of bytes allocated for the joints array
Joint** m_joints;
/// Current number of bodies in the island
uint32_t m_numberBodies;
/// Current number of contact manifold in the island
uint32_t m_numberContactManifolds;
/// Current number of joints in the island
uint32_t m_numberJoints;
/// Reference to the memory allocator
MemoryAllocator& m_memoryAllocator;
/// Number of bytes allocated for the bodies array
size_t m_numberAllocatedBytesBodies;
/// Number of bytes allocated for the contact manifolds array
size_t m_numberAllocatedBytesContactManifolds;
/// Number of bytes allocated for the joints array
size_t m_numberAllocatedBytesJoints;
// -------------------- Methods -------------------- //
/// Private assignment operator /// Private assignment operator
Island& operator=(const Island& island); Island& operator=(const Island& island);
/// Private copy-constructor /// Private copy-constructor
Island(const Island& island); Island(const Island& island);
public: public:
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
Island(uint32_t nbMaxBodies, uint32_t nbMaxContactManifolds, uint32_t nbMaxJoints, Island(uint32_t nbMaxBodies, uint32_t nbMaxContactManifolds, uint32_t nbMaxJoints,
MemoryAllocator& memoryAllocator); MemoryAllocator& memoryAllocator);
/// Destructor /// Destructor
~Island(); ~Island();
/// Add a body int32_to the island /// Add a body int32_to the island
void addBody(RigidBody* body); void addBody(RigidBody* body);
/// Add a contact manifold int32_to the island /// Add a contact manifold int32_to the island
void addContactManifold(ContactManifold* contactManifold); void addContactManifold(ContactManifold* contactManifold);
/// Add a joint int32_to the island /// Add a joint int32_to the island
void addJoint(Joint* joint); void addJoint(Joint* joint);
/// Return the number of bodies in the island /// Return the number of bodies in the island
uint32_t getNbBodies() const; uint32_t getNbBodies() const;
/// Return the number of contact manifolds in the island /// Return the number of contact manifolds in the island
uint32_t getNbContactManifolds() const; uint32_t getNbContactManifolds() const;
/// Return the number of joints in the island /// Return the number of joints in the island
uint32_t getNbJoints() const; uint32_t getNbJoints() const;
/// Return a pointer to the array of bodies /// Return a pointer to the array of bodies
RigidBody** getBodies(); RigidBody** getBodies();
/// Return a pointer to the array of contact manifolds /// Return a pointer to the array of contact manifolds
ContactManifold** getContactManifold(); ContactManifold** getContactManifold();
/// Return a pointer to the array of joints /// Return a pointer to the array of joints
Joint** getJoints(); Joint** getJoints();
// -------------------- Friendship -------------------- //
friend class DynamicsWorld; friend class DynamicsWorld;
}; };

View File

@ -23,8 +23,3 @@ Material::Material(const Material& material)
m_rollingResistance(material.m_rollingResistance), m_bounciness(material.m_bounciness) { m_rollingResistance(material.m_rollingResistance), m_bounciness(material.m_bounciness) {
} }
// Destructor
Material::~Material() {
}

View File

@ -4,65 +4,37 @@
* @license BSD 3 clauses (see license file) * @license BSD 3 clauses (see license file)
*/ */
#pragma once #pragma once
// Libraries
#include <cassert> #include <cassert>
#include <ephysics/configuration.hpp> #include <ephysics/configuration.hpp>
namespace ephysics { namespace ephysics {
// Class Material
/** /**
* This class contains the material properties of a rigid body that will be use for * This class contains the material properties of a rigid body that will be use for
* the dynamics simulation like the friction coefficient or the bounciness of the rigid * the dynamics simulation like the friction coefficient or the bounciness of the rigid
* body. * body.
*/ */
class Material { class Material {
private : private :
float m_frictionCoefficient; //!< Friction coefficient (positive value)
// -------------------- Attributes -------------------- // float m_rollingResistance; //!< Rolling resistance factor (positive value)
float m_bounciness; //!< Bounciness during collisions (between 0 and 1) where 1 is for a very bouncy body
/// Friction coefficient (positive value)
float m_frictionCoefficient;
/// Rolling resistance factor (positive value)
float m_rollingResistance;
/// Bounciness during collisions (between 0 and 1) where 1 is for a very bouncy body
float m_bounciness;
public : public :
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
Material(); Material();
/// Copy-constructor /// Copy-constructor
Material(const Material& material); Material(const Material& material);
/// Destructor
~Material();
/// Return the bounciness /// Return the bounciness
float getBounciness() const; float getBounciness() const;
/// Set the bounciness. /// Set the bounciness.
void setBounciness(float bounciness); void setBounciness(float bounciness);
/// Return the friction coefficient /// Return the friction coefficient
float getFrictionCoefficient() const; float getFrictionCoefficient() const;
/// Set the friction coefficient. /// Set the friction coefficient.
void setFrictionCoefficient(float frictionCoefficient); void setFrictionCoefficient(float frictionCoefficient);
/// Return the rolling resistance factor /// Return the rolling resistance factor
float getRollingResistance() const; float getRollingResistance() const;
/// Set the rolling resistance factor /// Set the rolling resistance factor
void setRollingResistance(float rollingResistance); void setRollingResistance(float rollingResistance);
/// Overloaded assignment operator /// Overloaded assignment operator
Material& operator=(const Material& material); Material& operator=(const Material& material);
}; };

View File

@ -16,8 +16,3 @@ OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, int32_t
m_cachedSeparatingAxis(1.0, 1.0, 1.0) { m_cachedSeparatingAxis(1.0, 1.0, 1.0) {
} }
// Destructor
OverlappingPair::~OverlappingPair() {
}

View File

@ -4,92 +4,56 @@
* @license BSD 3 clauses (see license file) * @license BSD 3 clauses (see license file)
*/ */
#pragma once #pragma once
// Libraries
#include <ephysics/collision/ContactManifoldSet.hpp> #include <ephysics/collision/ContactManifoldSet.hpp>
#include <ephysics/collision/ProxyShape.hpp> #include <ephysics/collision/ProxyShape.hpp>
#include <ephysics/collision/shapes/CollisionShape.hpp> #include <ephysics/collision/shapes/CollisionShape.hpp>
/// ReactPhysics3D namespace
namespace ephysics { namespace ephysics {
// Type for the overlapping pair ID // Type for the overlapping pair ID
typedef std::pair<uint32_t, uint32_t> overlappingpairid; typedef std::pair<uint32_t, uint32_t> overlappingpairid;
// Class OverlappingPair
/** /**
* This class represents a pair of two proxy collision shapes that are overlapping * @brief This class represents a pair of two proxy collision shapes that are overlapping
* during the broad-phase collision detection. It is created when * during the broad-phase collision detection. It is created when
* the two proxy collision shapes start to overlap and is destroyed when they do not * the two proxy collision shapes start to overlap and is destroyed when they do not
* overlap anymore. This class contains a contact manifold that * overlap anymore. This class contains a contact manifold that
* store all the contact points between the two bodies. * store all the contact points between the two bodies.
*/ */
class OverlappingPair { class OverlappingPair {
private: private:
ContactManifoldSet m_contactManifoldSet; //!< Set of persistent contact manifolds
// -------------------- Attributes -------------------- // vec3 m_cachedSeparatingAxis; //!< Cached previous separating axis
/// Set of persistent contact manifolds
ContactManifoldSet m_contactManifoldSet;
/// Cached previous separating axis
vec3 m_cachedSeparatingAxis;
// -------------------- Methods -------------------- //
/// Private copy-constructor /// Private copy-constructor
OverlappingPair(const OverlappingPair& pair); OverlappingPair(const OverlappingPair& pair);
/// Private assignment operator /// Private assignment operator
OverlappingPair& operator=(const OverlappingPair& pair); OverlappingPair& operator=(const OverlappingPair& pair);
public: public:
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, OverlappingPair(ProxyShape* shape1,
int32_t nbMaxContactManifolds, MemoryAllocator& memoryAllocator); ProxyShape* shape2,
int32_t nbMaxContactManifolds,
/// Destructor MemoryAllocator& memoryAllocator);
~OverlappingPair();
/// Return the pointer to first proxy collision shape /// Return the pointer to first proxy collision shape
ProxyShape* getShape1() const; ProxyShape* getShape1() const;
/// Return the pointer to second body /// Return the pointer to second body
ProxyShape* getShape2() const; ProxyShape* getShape2() const;
/// Add a contact to the contact cache /// Add a contact to the contact cache
void addContact(ContactPoint* contact); void addContact(ContactPoint* contact);
/// Update the contact cache /// Update the contact cache
void update(); void update();
/// Return the cached separating axis /// Return the cached separating axis
vec3 getCachedSeparatingAxis() const; vec3 getCachedSeparatingAxis() const;
/// Set the cached separating axis /// Set the cached separating axis
void setCachedSeparatingAxis(const vec3& axis); void setCachedSeparatingAxis(const vec3& axis);
/// Return the number of contacts in the cache /// Return the number of contacts in the cache
uint32_t getNbContactPoints() const; uint32_t getNbContactPoints() const;
/// Return the a reference to the contact manifold set /// Return the a reference to the contact manifold set
const ContactManifoldSet& getContactManifoldSet(); const ContactManifoldSet& getContactManifoldSet();
/// Clear the contact points of the contact manifold /// Clear the contact points of the contact manifold
void clearContactPoints(); void clearContactPoints();
/// Return the pair of bodies index /// Return the pair of bodies index
static overlappingpairid computeID(ProxyShape* shape1, ProxyShape* shape2); static overlappingpairid computeID(ProxyShape* shape1, ProxyShape* shape2);
/// Return the pair of bodies index of the pair /// Return the pair of bodies index of the pair
static bodyindexpair computeBodiesIndexPair(CollisionBody* body1, CollisionBody* body2); static bodyindexpair computeBodiesIndexPair(CollisionBody* body1, CollisionBody* body2);
// -------------------- Friendship -------------------- //
friend class DynamicsWorld; friend class DynamicsWorld;
}; };

View File

@ -6,238 +6,138 @@
#pragma once #pragma once
#ifdef IS_PROFILING_ACTIVE #ifdef IS_PROFILING_ACTIVE
// Libraries
#include <ephysics/configuration.hpp> #include <ephysics/configuration.hpp>
#include <ephysics/Timer.hpp> #include <ephysics/Timer.hpp>
/// ReactPhysics3D namespace
namespace ephysics { namespace ephysics {
// Class ProfileNode
/** /**
* It represents a profile sample in the profiler tree. * @brief It represents a profile sample in the profiler tree.
*/ */
class ProfileNode { class ProfileNode {
private : private :
const char* m_name; //!< Name of the node
// -------------------- Attributes -------------------- // uint32_t m_numberTotalCalls; //!< Total number of calls of this node
long double m_startTime; //!< Starting time of the sampling of corresponding block of code
/// Name of the node long double m_totalTime; //!< Total time spent in the block of code
const char* m_name; int32_t m_recursionCounter; //!< Recursion counter
ProfileNode* m_parentNode; //!< Pointer to the parent node
/// Total number of calls of this node ProfileNode* m_childNode; //!< Pointer to a child node
uint32_t m_numberTotalCalls; ProfileNode* m_siblingNode; //!< Pointer to a sibling node
/// Starting time of the sampling of corresponding block of code
long double m_startTime;
/// Total time spent in the block of code
long double m_totalTime;
/// Recursion counter
int32_t m_recursionCounter;
/// Pointer to the parent node
ProfileNode* m_parentNode;
/// Pointer to a child node
ProfileNode* m_childNode;
/// Pointer to a sibling node
ProfileNode* m_siblingNode;
public : public :
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
ProfileNode(const char* name, ProfileNode* parentNode); ProfileNode(const char* name, ProfileNode* parentNode);
/// Destructor /// Destructor
~ProfileNode(); ~ProfileNode();
/// Return a pointer to a sub node /// Return a pointer to a sub node
ProfileNode* findSubNode(const char* name); ProfileNode* findSubNode(const char* name);
/// Return a pointer to the parent node /// Return a pointer to the parent node
ProfileNode* getParentNode(); ProfileNode* getParentNode();
/// Return a pointer to a sibling node /// Return a pointer to a sibling node
ProfileNode* getSiblingNode(); ProfileNode* getSiblingNode();
/// Return a pointer to a child node /// Return a pointer to a child node
ProfileNode* getChildNode(); ProfileNode* getChildNode();
/// Return the name of the node /// Return the name of the node
const char* getName(); const char* getName();
/// Return the total number of call of the corresponding block of code /// Return the total number of call of the corresponding block of code
uint32_t getNbTotalCalls() const; uint32_t getNbTotalCalls() const;
/// Return the total time spent in the block of code /// Return the total time spent in the block of code
long double getTotalTime() const; long double getTotalTime() const;
/// Called when we enter the block of code corresponding to this profile node /// Called when we enter the block of code corresponding to this profile node
void enterBlockOfCode(); void enterBlockOfCode();
/// Called when we exit the block of code corresponding to this profile node /// Called when we exit the block of code corresponding to this profile node
bool exitBlockOfCode(); bool exitBlockOfCode();
/// Reset the profiling of the node /// Reset the profiling of the node
void reset(); void reset();
/// Destroy the node /// Destroy the node
void destroy(); void destroy();
}; };
// Class ProfileNodeIterator
/** /**
* This class allows us to iterator over the profiler tree. * @brief This class allows us to iterator over the profiler tree.
*/ */
class ProfileNodeIterator { class ProfileNodeIterator {
private : private :
ProfileNode* m_currentParentNode; //!< Current parent node
// -------------------- Attributes -------------------- // ProfileNode* m_currentChildNode; //!< Current child node
/// Current parent node
ProfileNode* m_currentParentNode;
/// Current child node
ProfileNode* m_currentChildNode;
public : public :
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
ProfileNodeIterator(ProfileNode* startingNode); ProfileNodeIterator(ProfileNode* startingNode);
/// Go to the first node /// Go to the first node
void first(); void first();
/// Go to the next node /// Go to the next node
void next(); void next();
/// Enter a given child node /// Enter a given child node
void enterChild(int32_t index); void enterChild(int32_t index);
/// Enter a given parent node /// Enter a given parent node
void enterParent(); void enterParent();
/// Return true if we are at the root of the profiler tree /// Return true if we are at the root of the profiler tree
bool isRoot(); bool isRoot();
/// Return true if we are at the end of a branch of the profiler tree /// Return true if we are at the end of a branch of the profiler tree
bool isEnd(); bool isEnd();
/// Return the name of the current node /// Return the name of the current node
const char* getCurrentName(); const char* getCurrentName();
/// Return the total time of the current node /// Return the total time of the current node
long double getCurrentTotalTime(); long double getCurrentTotalTime();
/// Return the total number of calls of the current node /// Return the total number of calls of the current node
uint32_t getCurrentNbTotalCalls(); uint32_t getCurrentNbTotalCalls();
/// Return the name of the current parent node /// Return the name of the current parent node
const char* getCurrentParentName(); const char* getCurrentParentName();
/// Return the total time of the current parent node /// Return the total time of the current parent node
long double getCurrentParentTotalTime(); long double getCurrentParentTotalTime();
/// Return the total number of calls of the current parent node /// Return the total number of calls of the current parent node
uint32_t getCurrentParentNbTotalCalls(); uint32_t getCurrentParentNbTotalCalls();
}; };
// Class Profiler
/** /**
* This is the main class of the profiler. This profiler is based on "Real-Time Hierarchical * @brief This is the main class of the profiler. This profiler is based on "Real-Time Hierarchical
* Profiling" article from "Game Programming Gems 3" by Greg Hjelstrom and Byon Garrabrant. * Profiling" article from "Game Programming Gems 3" by Greg Hjelstrom and Byon Garrabrant.
*/ */
class Profiler { class Profiler {
private : private :
static ProfileNode m_rootNode; //!< Root node of the profiler tree
// -------------------- Attributes -------------------- // static ProfileNode* m_currentNode; //!< Current node in the current execution
static uint32_t m_frameCounter; //!< Frame counter
/// Root node of the profiler tree static long double m_profilingStartTime; //!< Starting profiling time
static ProfileNode m_rootNode; private:
/// Current node in the current execution
static ProfileNode* m_currentNode;
/// Frame counter
static uint32_t m_frameCounter;
/// Starting profiling time
static long double m_profilingStartTime;
/// Recursively print32_t the report of a given node of the profiler tree
static void print32_tRecursiveNodeReport(ProfileNodeIterator* iterator, static void print32_tRecursiveNodeReport(ProfileNodeIterator* iterator,
int32_t spacing, int32_t spacing,
std::ostream& outputStream); std::ostream& outputStream);
public : public :
// -------------------- Methods -------------------- //
/// Method called when we want to start profiling a block of code. /// Method called when we want to start profiling a block of code.
static void startProfilingBlock(const char *name); static void startProfilingBlock(const char *name);
/// Method called at the end of the scope where the /// Method called at the end of the scope where the
/// startProfilingBlock() method has been called. /// startProfilingBlock() method has been called.
static void stopProfilingBlock(); static void stopProfilingBlock();
/// Reset the timing data of the profiler (but not the profiler tree structure) /// Reset the timing data of the profiler (but not the profiler tree structure)
static void reset(); static void reset();
/// Return the number of frames /// Return the number of frames
static uint32_t getNbFrames(); static uint32_t getNbFrames();
/// Return the elasped time since the start/reset of the profiling /// Return the elasped time since the start/reset of the profiling
static long double getElapsedTimeSinceStart(); static long double getElapsedTimeSinceStart();
/// Increment the frame counter /// Increment the frame counter
static void incrementFrameCounter(); static void incrementFrameCounter();
/// Return an iterator over the profiler tree starting at the root /// Return an iterator over the profiler tree starting at the root
static ProfileNodeIterator* getIterator(); static ProfileNodeIterator* getIterator();
/// Print32_t the report of the profiler in a given output stream /// Print32_t the report of the profiler in a given output stream
static void print32_tReport(std::ostream& outputStream); static void print32_tReport(std::ostream& outputStream);
/// Destroy a previously allocated iterator /// Destroy a previously allocated iterator
static void destroyIterator(ProfileNodeIterator* iterator); static void destroyIterator(ProfileNodeIterator* iterator);
/// Destroy the profiler (release the memory) /// Destroy the profiler (release the memory)
static void destroy(); static void destroy();
}; };
// Class ProfileSample
/** /**
* This class is used to represent a profile sample. It is constructed at the * @brief This class is used to represent a profile sample. It is constructed at the
* beginning of a code block we want to profile and destructed at the end of the * beginning of a code block we want to profile and destructed at the end of the
* scope to profile. * scope to profile.
*/ */
class ProfileSample { class ProfileSample {
public : public :
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
ProfileSample(const char* name) { ProfileSample(const char* name) {
// Ask the profiler to start profiling a block of code // Ask the profiler to start profiling a block of code
Profiler::startProfilingBlock(name); Profiler::startProfilingBlock(name);
} }
/// Destructor /// Destructor
~ProfileSample() { ~ProfileSample() {
// Tell the profiler to stop profiling a block of code // Tell the profiler to stop profiling a block of code
Profiler::stopProfilingBlock(); Profiler::stopProfilingBlock();
} }
@ -248,12 +148,12 @@ class ProfileSample {
// Return true if we are at the root of the profiler tree // Return true if we are at the root of the profiler tree
inline bool ProfileNodeIterator::isRoot() { inline bool ProfileNodeIterator::isRoot() {
return (m_currentParentNode->getParentNode() == NULL); return (m_currentParentNode->getParentNode() == nullptr);
} }
// Return true if we are at the end of a branch of the profiler tree // Return true if we are at the end of a branch of the profiler tree
inline bool ProfileNodeIterator::isEnd() { inline bool ProfileNodeIterator::isEnd() {
return (m_currentChildNode == NULL); return (m_currentChildNode == nullptr);
} }
// Return the name of the current node // Return the name of the current node
@ -359,7 +259,7 @@ inline void Profiler::destroy() {
} }
#else // In profile is not active #else
// Empty macro in case profiling is not active // Empty macro in case profiling is not active
#define PROFILE(name) #define PROFILE(name)

View File

@ -22,82 +22,47 @@
/// Namespace ReactPhysics3D /// Namespace ReactPhysics3D
namespace ephysics { namespace ephysics {
// Class Timer
/** /**
* This class will take care of the time in the physics engine. It * @brief This class will take care of the time in the physics engine. It
* uses functions that depend on the current platform to get the * uses functions that depend on the current platform to get the
* current time. * current time.
*/ */
class Timer { class Timer {
private : private :
double m_timeStep; //!< Timestep dt of the physics engine (timestep > 0.0)
// -------------------- Attributes -------------------- // long double m_lastUpdateTime; //!< Last time the timer has been updated
long double m_deltaTime; //!< Time difference between the two last timer update() calls
/// Timestep dt of the physics engine (timestep > 0.0) double m_accumulator; //!< Used to fix the time step and avoid strange time effects
double m_timeStep; bool m_isRunning; //!< True if the timer is running
/// Last time the timer has been updated
long double m_lastUpdateTime;
/// Time difference between the two last timer update() calls
long double m_deltaTime;
/// Used to fix the time step and avoid strange time effects
double m_accumulator;
/// True if the timer is running
bool m_isRunning;
// -------------------- Methods -------------------- //
/// Private copy-constructor /// Private copy-constructor
Timer(const Timer& timer); Timer(const Timer& timer);
/// Private assignment operator /// Private assignment operator
Timer& operator=(const Timer& timer); Timer& operator=(const Timer& timer);
public : public :
// -------------------- Methods -------------------- //
/// Constructor /// Constructor
Timer(double timeStep); Timer(double timeStep);
/// Destructor /// Destructor
virtual ~Timer(); virtual ~Timer();
/// Return the timestep of the physics engine /// Return the timestep of the physics engine
double getTimeStep() const; double getTimeStep() const;
/// Set the timestep of the physics engine /// Set the timestep of the physics engine
void setTimeStep(double timeStep); void setTimeStep(double timeStep);
/// Return the current time of the physics engine /// Return the current time of the physics engine
long double getPhysicsTime() const; long double getPhysicsTime() const;
/// Start the timer /// Start the timer
void start(); void start();
/// Stop the timer /// Stop the timer
void stop(); void stop();
/// Return true if the timer is running /// Return true if the timer is running
bool getIsRunning() const; bool getIsRunning() const;
/// True if it's possible to take a new step /// True if it's possible to take a new step
bool isPossibleToTakeStep() const; bool isPossibleToTakeStep() const;
/// Compute the time since the last update() call and add it to the accumulator /// Compute the time since the last update() call and add it to the accumulator
void update(); void update();
/// Take a new step => update the timer by adding the timeStep value to the current time /// Take a new step => update the timer by adding the timeStep value to the current time
void nextStep(); void nextStep();
/// Compute the int32_terpolation factor /// Compute the int32_terpolation factor
float computeInterpolationFactor(); float computeInterpolationFactor();
/// Return the current time of the system in seconds /// Return the current time of the system in seconds
static long double getCurrentSystemTime(); static long double getCurrentSystemTime();
}; };