Refactor the Profiler. Now there is one profiler instance per CollisionWorld/DynamicsWorld instance instead of a static one

This commit is contained in:
Daniel Chappuis 2017-11-10 19:57:50 +01:00
parent 222636391e
commit e9709c3db5
49 changed files with 790 additions and 210 deletions

View File

@ -74,6 +74,13 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape,
sizeof(ProxyShape))) ProxyShape(this, collisionShape,
transform, decimal(1));
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
proxyShape->setProfiler(mProfiler);
#endif
// Add it to the list of proxy collision shapes of the body
if (mProxyCollisionShapes == nullptr) {
mProxyCollisionShapes = proxyShape;

View File

@ -36,6 +36,7 @@
#include "collision/RaycastInfo.h"
#include "memory/PoolAllocator.h"
#include "configuration.h"
#include "engine/Profiler.h"
/// Namespace reactphysics3d
namespace reactphysics3d {
@ -85,6 +86,13 @@ class CollisionBody : public Body {
/// Reference to the world the body belongs to
CollisionWorld& mWorld;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
// -------------------- Methods -------------------- //
/// Reset the contact manifold lists
@ -177,6 +185,13 @@ class CollisionBody : public Body {
/// Return the body local-space coordinates of a vector given in the world-space coordinates
Vector3 getLocalVector(const Vector3& worldVector) const;
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
virtual void setProfiler(Profiler* profiler);
#endif
// -------------------- Friendship -------------------- //
friend class CollisionWorld;
@ -313,6 +328,15 @@ inline bool CollisionBody::testAABBOverlap(const AABB& worldAABB) const {
return worldAABB.testCollision(getAABB());
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void CollisionBody::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
}
#endif

View File

@ -228,6 +228,13 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape,
sizeof(ProxyShape))) ProxyShape(this, collisionShape,
transform, mass);
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
proxyShape->setProfiler(mProfiler);
#endif
// Add it to the list of proxy collision shapes of the body
if (mProxyCollisionShapes == nullptr) {
mProxyCollisionShapes = proxyShape;
@ -410,7 +417,7 @@ void RigidBody::recomputeMassInformation() {
// Update the broad-phase state for this body (because it has moved for instance)
void RigidBody::updateBroadPhaseState() const {
PROFILE("RigidBody::updateBroadPhaseState()");
PROFILE("RigidBody::updateBroadPhaseState()", mProfiler);
DynamicsWorld& world = static_cast<DynamicsWorld&>(mWorld);
const Vector3 displacement = world.mTimeStep * mLinearVelocity;
@ -427,3 +434,22 @@ void RigidBody::updateBroadPhaseState() const {
}
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
void RigidBody::setProfiler(Profiler* profiler) {
CollisionBody::setProfiler(profiler);
// Set the profiler for each proxy shape
ProxyShape* proxyShape = getProxyShapesList();
while (proxyShape != nullptr) {
proxyShape->setProfiler(profiler);
proxyShape = proxyShape->getNext();
}
}
#endif

View File

@ -227,6 +227,13 @@ class RigidBody : public CollisionBody {
/// the collision shapes attached to the body.
void recomputeMassInformation();
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler) override;
#endif
// -------------------- Friendship -------------------- //
friend class DynamicsWorld;

View File

@ -57,12 +57,19 @@ CollisionDetection::CollisionDetection(CollisionWorld* world, PoolAllocator& mem
// Fill-in the collision detection matrix with algorithms
fillInCollisionMatrix();
#ifdef IS_PROFILING_ACTIVE
mProfiler = nullptr;
#endif
}
// Compute the collision detection
void CollisionDetection::computeCollisionDetection() {
PROFILE("CollisionDetection::computeCollisionDetection()");
PROFILE("CollisionDetection::computeCollisionDetection()", mProfiler);
// Compute the broad-phase collision detection
computeBroadPhase();
@ -80,7 +87,7 @@ void CollisionDetection::computeCollisionDetection() {
// Compute the broad-phase collision detection
void CollisionDetection::computeBroadPhase() {
PROFILE("CollisionDetection::computeBroadPhase()");
PROFILE("CollisionDetection::computeBroadPhase()", mProfiler);
// If new collision shapes have been added to bodies
if (mIsCollisionShapesAdded) {
@ -95,7 +102,7 @@ void CollisionDetection::computeBroadPhase() {
// Compute the middle-phase collision detection
void CollisionDetection::computeMiddlePhase() {
PROFILE("CollisionDetection::computeMiddlePhase()");
PROFILE("CollisionDetection::computeMiddlePhase()", mProfiler);
// For each possible collision pair of bodies
map<overlappingpairid, OverlappingPair*>::iterator it;
@ -219,6 +226,13 @@ void CollisionDetection::computeConvexVsConcaveMiddlePhase(OverlappingPair* pair
MiddlePhaseTriangleCallback middlePhaseCallback(pair, concaveProxyShape, convexProxyShape,
concaveShape, allocator);
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
middlePhaseCallback.setProfiler(mProfiler);
#endif
// Compute the convex shape AABB in the local-space of the convex shape
const Transform convexToConcaveTransform = concaveProxyShape->getLocalToWorldTransform().getInverse() *
convexProxyShape->getLocalToWorldTransform();
@ -236,7 +250,7 @@ void CollisionDetection::computeConvexVsConcaveMiddlePhase(OverlappingPair* pair
// Compute the narrow-phase collision detection
void CollisionDetection::computeNarrowPhase() {
PROFILE("CollisionDetection::computeNarrowPhase()");
PROFILE("CollisionDetection::computeNarrowPhase()", mProfiler);
NarrowPhaseInfo* currentNarrowPhaseInfo = mNarrowPhaseInfoList;
while (currentNarrowPhaseInfo != nullptr) {
@ -444,90 +458,6 @@ void CollisionDetection::reportAllContacts() {
}
}
// Process the potential contacts where one collion is a concave shape.
// This method processes the concave triangle mesh collision using the smooth mesh collision algorithm described
// by Pierre Terdiman (http://www.codercorner.com/MeshContacts.pdf). This is used to avoid the collision
// issue with some internal edges.
void CollisionDetection::processSmoothMeshContacts(OverlappingPair* pair) {
// // Set with the triangle vertices already processed to void further contacts with same triangle
// std::unordered_multimap<int, Vector3> processTriangleVertices;
// std::vector<SmoothMeshContactInfo*> smoothContactPoints;
// // If the collision shape 1 is the triangle
// bool isFirstShapeTriangle = pair->getShape1()->getCollisionShape()->getType() == CollisionShapeType::TRIANGLE;
// assert(isFirstShapeTriangle || pair->getShape2()->getCollisionShape()->getType() == CollisionShapeType::TRIANGLE);
// assert(!isFirstShapeTriangle || pair->getShape2()->getCollisionShape()->getType() != CollisionShapeType::TRIANGLE);
// const TriangleShape* triangleShape = nullptr;
// if (isFirstShapeTriangle) {
// triangleShape = static_cast<const TriangleShape*>(pair->getShape1()->getCollisionShape());
// }
// else {
// triangleShape = static_cast<const TriangleShape*>(pair->getShape2()->getCollisionShape());
// }
// assert(triangleShape != nullptr);
// // Get the temporary memory allocator
// Allocator& allocator = pair->getTemporaryAllocator();
// // For each potential contact manifold of the pair
// ContactManifoldInfo* potentialManifold = pair->getPotentialContactManifolds();
// while (potentialManifold != nullptr) {
// // For each contact point of the potential manifold
// ContactPointInfo* contactPointInfo = potentialManifold->getFirstContactPointInfo();
// while (contactPointInfo != nullptr) {
// // Compute the barycentric coordinates of the point in the triangle
// decimal u, v, w;
// computeBarycentricCoordinatesInTriangle(triangleShape->getVertexPosition(0),
// triangleShape->getVertexPosition(1),
// triangleShape->getVertexPosition(2),
// isFirstShapeTriangle ? contactPointInfo->localPoint1 : contactPointInfo->localPoint2,
// u, v, w);
// int nbZeros = 0;
// bool isUZero = approxEqual(u, 0, 0.0001);
// bool isVZero = approxEqual(v, 0, 0.0001);
// bool isWZero = approxEqual(w, 0, 0.0001);
// if (isUZero) nbZeros++;
// if (isVZero) nbZeros++;
// if (isWZero) nbZeros++;
// // If the triangle contact point is on a triangle vertex of a triangle edge
// if (nbZeros == 1 || nbZeros == 2) {
// // Create a smooth mesh contact info
// SmoothMeshContactInfo* smoothContactInfo = new (allocator.allocate(sizeof(SmoothMeshContactInfo)))
// SmoothMeshContactInfo(potentialManifold, contactInfo, isFirstShapeTriangle,
// triangleShape->getVertexPosition(0),
// triangleShape->getVertexPosition(1),
// triangleShape->getVertexPosition(2));
// smoothContactPoints.push_back(smoothContactInfo);
// // Remove the contact point info from the manifold. If the contact point will be kept in the future, we
// // will put the contact point back in the manifold.
// ...
// }
// // Note that we do not remove the contact points that are not on the vertices or edges of the triangle
// // from the contact manifold because we know we will keep to contact points. We only remove the vertices
// // and edges contact points for the moment. If those points will be kept in the future, we will have to
// // put them back again in the contact manifold
// }
// potentialManifold = potentialManifold->mNext;
// }
// // Sort the list of narrow-phase contacts according to their penetration depth
// std::sort(smoothContactPoints.begin(), smoothContactPoints.end(), ContactsDepthCompare());
// ...
}
// Compute the middle-phase collision detection between two proxy shapes
NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(OverlappingPair* pair) {

View File

@ -100,6 +100,13 @@ class CollisionDetection {
/// True if some collision shapes have been added previously
bool mIsCollisionShapesAdded;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
// -------------------- Methods -------------------- //
/// Compute the broad-phase collision detection
@ -143,6 +150,7 @@ class CollisionDetection {
/// Process the potential contacts where one collion is a concave shape
void processSmoothMeshContacts(OverlappingPair* pair);
public :
@ -219,6 +227,13 @@ class CollisionDetection {
/// Return a reference to the world memory allocator
PoolAllocator& getWorldMemoryAllocator();
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler);
#endif
/// Return the world-space AABB of a given proxy shape
const AABB getWorldAABB(const ProxyShape* proxyShape) const;
@ -234,6 +249,14 @@ inline void CollisionDetection::setCollisionDispatch(CollisionDispatch* collisio
// Fill-in the collision matrix with the new algorithms to use
fillInCollisionMatrix();
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
mCollisionDispatch->setProfiler(mProfiler);
#endif
}
// Add a body to the collision detection
@ -298,7 +321,7 @@ inline void CollisionDetection::raycast(RaycastCallback* raycastCallback,
const Ray& ray,
unsigned short raycastWithCategoryMaskBits) const {
PROFILE("CollisionDetection::raycast()");
PROFILE("CollisionDetection::raycast()", mProfiler);
RaycastTest rayCastTest(raycastCallback);
@ -312,6 +335,17 @@ inline CollisionWorld* CollisionDetection::getWorld() {
return mWorld;
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void CollisionDetection::setProfiler(Profiler* profiler) {
mProfiler = profiler;
mBroadPhaseAlgorithm.setProfiler(profiler);
mCollisionDispatch->setProfiler(profiler);
}
#endif
}
#endif

View File

@ -38,6 +38,13 @@ void MiddlePhaseTriangleCallback::testTriangle(uint meshSubPart, uint triangleIn
TriangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2],
verticesNormals, meshSubPart, triangleIndex);
#ifdef IS_PROFILING_ACTIVE
// Set the profiler to the triangle shape
triangleShape->setProfiler(mProfiler);
#endif
bool isShape1Convex = mOverlappingPair->getShape1()->getCollisionShape()->isConvex();
ProxyShape* shape1 = isShape1Convex ? mConvexProxyShape : mConcaveProxyShape;
ProxyShape* shape2 = isShape1Convex ? mConcaveProxyShape : mConvexProxyShape;

View File

@ -58,6 +58,13 @@ class MiddlePhaseTriangleCallback : public TriangleCallback {
/// Reference to the single-frame memory allocator
Allocator& mAllocator;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
public:
/// Pointer to the first element of the linked-list of narrow-phase info
@ -77,6 +84,16 @@ class MiddlePhaseTriangleCallback : public TriangleCallback {
/// Test collision between a triangle and the convex mesh shape
virtual void testTriangle(uint meshSubpart, uint triangleIndex, const Vector3* trianglePoints,
const Vector3* verticesNormals) override;
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
};
}

View File

@ -85,6 +85,13 @@ class ProxyShape {
/// proxy shape will collide with every collision categories by default.
unsigned short mCollideWithMaskBits;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
// -------------------- Methods -------------------- //
/// Return the collision shape
@ -170,6 +177,13 @@ class ProxyShape {
/// Set the local scaling vector of the collision shape
virtual void setLocalScaling(const Vector3& scaling);
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler);
#endif
// -------------------- Friendship -------------------- //
friend class OverlappingPair;
@ -359,6 +373,18 @@ inline bool ProxyShape::testAABBOverlap(const AABB& worldAABB) const {
return worldAABB.testCollision(getWorldAABB());
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void ProxyShape::setProfiler(Profiler* profiler) {
mProfiler = profiler;
mCollisionShape->setProfiler(profiler);
}
#endif
}
#endif

View File

@ -44,6 +44,13 @@ BroadPhaseAlgorithm::BroadPhaseAlgorithm(CollisionDetection& collisionDetection)
// Allocate memory for the array of potential overlapping pairs
mPotentialPairs = (BroadPhasePair*) malloc(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair));
assert(mPotentialPairs != nullptr);
#ifdef IS_PROFILING_ACTIVE
mProfiler = nullptr;
#endif
}
// Destructor

View File

@ -162,6 +162,13 @@ class BroadPhaseAlgorithm {
/// Reference to the collision detection object
CollisionDetection& mCollisionDetection;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
public :
// -------------------- Methods -------------------- //
@ -215,8 +222,15 @@ class BroadPhaseAlgorithm {
const AABB& getFatAABB(int broadPhaseId) const;
/// Ray casting method
void raycast(const Ray& ray, RaycastTest& raycastTest,
unsigned short raycastWithCategoryMaskBits) const;
void raycast(const Ray& ray, RaycastTest& raycastTest, unsigned short raycastWithCategoryMaskBits) const;
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler);
#endif
};
// Method used to compare two pairs for sorting algorithm
@ -252,7 +266,7 @@ inline const AABB& BroadPhaseAlgorithm::getFatAABB(int broadPhaseId) const {
inline void BroadPhaseAlgorithm::raycast(const Ray& ray, RaycastTest& raycastTest,
unsigned short raycastWithCategoryMaskBits) const {
PROFILE("BroadPhaseAlgorithm::raycast()");
PROFILE("BroadPhaseAlgorithm::raycast()", mProfiler);
BroadPhaseRaycastCallback broadPhaseRaycastCallback(mDynamicAABBTree, raycastWithCategoryMaskBits, raycastTest);
@ -264,6 +278,16 @@ inline ProxyShape* BroadPhaseAlgorithm::getProxyShapeForBroadPhaseId(int broadPh
return static_cast<ProxyShape*>(mDynamicAABBTree.getNodeDataPointer(broadPhaseId));
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void BroadPhaseAlgorithm::setProfiler(Profiler* profiler) {
mProfiler = profiler;
mDynamicAABBTree.setProfiler(profiler);
}
#endif
}
#endif

View File

@ -171,7 +171,7 @@ void DynamicAABBTree::removeObject(int nodeID) {
/// (this can be useful if the shape AABB has become much smaller than the previous one for instance).
bool DynamicAABBTree::updateObject(int nodeID, const AABB& newAABB, const Vector3& displacement, bool forceReinsert) {
PROFILE("DynamicAABBTree::updateObject()");
PROFILE("DynamicAABBTree::updateObject()", mProfiler);
assert(nodeID >= 0 && nodeID < mNbAllocatedNodes);
assert(mNodes[nodeID].isLeaf());
@ -633,7 +633,7 @@ void DynamicAABBTree::reportAllShapesOverlappingWithAABB(const AABB& aabb,
// Ray casting method
void DynamicAABBTree::raycast(const Ray& ray, DynamicAABBTreeRaycastCallback &callback) const {
PROFILE("DynamicAABBTree::raycast()");
PROFILE("DynamicAABBTree::raycast()", mProfiler);
decimal maxFraction = ray.maxFraction;

View File

@ -155,6 +155,13 @@ class DynamicAABBTree {
/// without triggering a large modification of the tree which can be costly
decimal mExtraAABBGap;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
// -------------------- Methods -------------------- //
/// Allocate and return a node to use in the tree
@ -237,6 +244,14 @@ class DynamicAABBTree {
/// Clear all the nodes and reset the tree
void reset();
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler);
#endif
};
// Return true if the node is a leaf of the tree
@ -292,6 +307,15 @@ inline int DynamicAABBTree::addObject(const AABB& aabb, void* data) {
return nodeId;
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void DynamicAABBTree::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
}
#endif

View File

@ -41,7 +41,15 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh
// First, we run the GJK algorithm
GJKAlgorithm gjkAlgorithm;
SATAlgorithm satAlgorithm;
SATAlgorithm satAlgorithm;
#ifdef IS_PROFILING_ACTIVE
gjkAlgorithm.setProfiler(mProfiler);
satAlgorithm.setProfiler(mProfiler);
#endif
GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, reportContacts);
narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true;

View File

@ -41,6 +41,13 @@ class CollisionDispatch {
protected:
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
public:
/// Constructor
@ -49,13 +56,29 @@ class CollisionDispatch {
/// Destructor
virtual ~CollisionDispatch() = default;
/// Select and return the narrow-phase collision detection algorithm to
/// use between two types of collision shapes.
virtual NarrowPhaseAlgorithm* selectAlgorithm(int shape1Type,
int shape2Type)=0;
virtual NarrowPhaseAlgorithm* selectAlgorithm(int shape1Type, int shape2Type)=0;
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
virtual void setProfiler(Profiler* profiler);
#endif
};
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void CollisionDispatch::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
}
#endif

View File

@ -38,6 +38,13 @@ bool ConvexPolyhedronVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo*
// Run the SAT algorithm to find the separating axis and compute contact point
SATAlgorithm satAlgorithm;
#ifdef IS_PROFILING_ACTIVE
satAlgorithm.setProfiler(mProfiler);
#endif
bool isColliding = satAlgorithm.testCollisionConvexPolyhedronVsConvexPolyhedron(narrowPhaseInfo, reportContacts);
narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true;

View File

@ -77,8 +77,33 @@ class DefaultCollisionDispatch : public CollisionDispatch {
/// Select and return the narrow-phase collision detection algorithm to
/// use between two types of collision shapes.
virtual NarrowPhaseAlgorithm* selectAlgorithm(int type1, int type2) override;
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
virtual void setProfiler(Profiler* profiler) override;
#endif
};
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void DefaultCollisionDispatch::setProfiler(Profiler* profiler) {
CollisionDispatch::setProfiler(profiler);
mSphereVsSphereAlgorithm.setProfiler(profiler);
mCapsuleVsCapsuleAlgorithm.setProfiler(profiler);
mSphereVsCapsuleAlgorithm.setProfiler(profiler);
mSphereVsConvexPolyhedronAlgorithm.setProfiler(profiler);
mCapsuleVsConvexPolyhedronAlgorithm.setProfiler(profiler);
mConvexPolyhedronVsConvexPolyhedronAlgorithm.setProfiler(profiler);
}
#endif
}
#endif

View File

@ -49,7 +49,7 @@ using namespace reactphysics3d;
/// the correct penetration depth and contact points between the enlarged objects.
GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) {
PROFILE("GJKAlgorithm::testCollision()");
PROFILE("GJKAlgorithm::testCollision()", mProfiler);
Vector3 suppA; // Support point of object A
Vector3 suppB; // Support point of object B

View File

@ -62,6 +62,13 @@ class GJKAlgorithm {
// -------------------- Attributes -------------------- //
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
// -------------------- Methods -------------------- //
public :
@ -94,8 +101,25 @@ class GJKAlgorithm {
/// Ray casting algorithm agains a convex collision shape using the GJK Algorithm
bool raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& raycastInfo);
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler);
#endif
};
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void GJKAlgorithm::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
}
#endif

View File

@ -67,6 +67,13 @@ class NarrowPhaseAlgorithm {
// -------------------- Attributes -------------------- //
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
public :
// -------------------- Methods -------------------- //
@ -85,8 +92,25 @@ class NarrowPhaseAlgorithm {
/// Compute a contact info if the two bounding volume collide
virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts)=0;
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler);
#endif
};
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void NarrowPhaseAlgorithm::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
}
#endif

View File

@ -47,7 +47,7 @@ const decimal SATAlgorithm::SAME_SEPARATING_AXIS_BIAS = decimal(0.001);
// Test collision between a sphere and a convex mesh
bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const {
PROFILE("SATAlgorithm::testCollisionSphereVsConvexPolyhedron()");
PROFILE("SATAlgorithm::testCollisionSphereVsConvexPolyhedron()", mProfiler);
bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE;
@ -139,7 +139,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint faceInd
// Test collision between a capsule and a convex mesh
bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const {
PROFILE("SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron()");
PROFILE("SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron()", mProfiler);
bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE;
@ -448,7 +448,7 @@ bool SATAlgorithm::isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, c
// Test collision between two convex polyhedrons
bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const {
PROFILE("SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron()");
PROFILE("SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron()", mProfiler);
assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON);
assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON);

View File

@ -50,6 +50,13 @@ class SATAlgorithm {
/// make sure the contact manifold does not change too much between frames.
static const decimal SAME_SEPARATING_AXIS_BIAS;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
// -------------------- Methods -------------------- //
/// Return true if two edges of two polyhedrons build a minkowski face (and can therefore be a separating axis)
@ -138,8 +145,26 @@ class SATAlgorithm {
/// Test collision between two convex meshes
bool testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const;
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler);
#endif
};
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void SATAlgorithm::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
}
#endif

View File

@ -43,6 +43,13 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPha
// First, we run the GJK algorithm
GJKAlgorithm gjkAlgorithm;
#ifdef IS_PROFILING_ACTIVE
gjkAlgorithm.setProfiler(mProfiler);
#endif
GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, reportContacts);
narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true;
@ -60,6 +67,13 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPha
// Run the SAT algorithm to find the separating axis and compute contact point
SATAlgorithm satAlgorithm;
#ifdef IS_PROFILING_ACTIVE
satAlgorithm.setProfiler(mProfiler);
#endif
bool isColliding = satAlgorithm.testCollisionSphereVsConvexPolyhedron(narrowPhaseInfo, reportContacts);
narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false;

View File

@ -48,7 +48,7 @@ CollisionShape::CollisionShape(CollisionShapeName name, CollisionShapeType type)
*/
void CollisionShape::computeAABB(AABB& aabb, const Transform& transform) const {
PROFILE("CollisionShape::computeAABB()");
PROFILE("CollisionShape::computeAABB()", mProfiler);
// Get the local bounds in x,y and z direction
Vector3 minBounds;

View File

@ -35,6 +35,7 @@
#include "AABB.h"
#include "collision/RaycastInfo.h"
#include "memory/PoolAllocator.h"
#include "engine/Profiler.h"
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -69,6 +70,13 @@ class CollisionShape {
/// Scaling vector of the collision shape
Vector3 mScaling;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
// -------------------- Methods -------------------- //
@ -124,6 +132,13 @@ class CollisionShape {
/// Compute the world-space AABB of the collision shape given a transform
virtual void computeAABB(AABB& aabb, const Transform& transform) const;
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
virtual void setProfiler(Profiler* profiler);
#endif
// -------------------- Friendship -------------------- //
friend class ProxyShape;
@ -156,6 +171,16 @@ inline void CollisionShape::setLocalScaling(const Vector3& scaling) {
mScaling = scaling;
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void CollisionShape::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
}
#endif

View File

@ -113,11 +113,18 @@ void ConcaveMeshShape::testAllTriangles(TriangleCallback& callback, const AABB&
/// the ray hits many triangles.
bool ConcaveMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
PROFILE("ConcaveMeshShape::raycast()");
PROFILE("ConcaveMeshShape::raycast()", mProfiler);
// Create the callback object that will compute ray casting against triangles
ConcaveMeshRaycastCallback raycastCallback(mDynamicAABBTree, *this, proxyShape, raycastInfo, ray);
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
raycastCallback.setProfiler(mProfiler);
#endif
// Ask the Dynamic AABB Tree to report all AABB nodes that are hit by the ray.
// The raycastCallback object will then compute ray casting against the triangles
// in the hit AABBs.
@ -159,6 +166,13 @@ void ConcaveMeshRaycastCallback::raycastTriangles() {
TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2],
verticesNormals, data[0], data[1]);
triangleShape.setRaycastTestType(mConcaveMeshShape.getRaycastTestType());
#ifdef IS_PROFILING_ACTIVE
// Set the profiler to the triangle shape
triangleShape.setProfiler(mProfiler);
#endif
// Ray casting test against the collision shape
RaycastInfo raycastInfo;

View File

@ -78,6 +78,13 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback {
const Ray& mRay;
bool mIsHit;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
public:
// Constructor
@ -98,6 +105,15 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback {
bool getIsHit() const {
return mIsHit;
}
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
};
// Class ConcaveMeshShape
@ -165,6 +181,13 @@ class ConcaveMeshShape : public ConcaveShape {
/// Use a callback method on all triangles of the concave shape inside a given AABB
virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const override;
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
virtual void setProfiler(Profiler* profiler) override;
#endif
// ---------- Friendship ----------- //
friend class ConvexTriangleAABBOverlapCallback;
@ -239,6 +262,18 @@ inline void ConvexTriangleAABBOverlapCallback::notifyOverlappingNode(int nodeId)
mTriangleTestCallback.testTriangle(data[0], data[1], trianglePoints, verticesNormals);
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void ConcaveMeshShape::setProfiler(Profiler* profiler) {
CollisionShape::setProfiler(profiler);
mDynamicAABBTree.setProfiler(profiler);
}
#endif
}
#endif

View File

@ -217,10 +217,17 @@ bool HeightFieldShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxySh
// TODO : Implement raycasting without using an AABB for the ray
// but using a dynamic AABB tree or octree instead
PROFILE("HeightFieldShape::raycast()");
PROFILE("HeightFieldShape::raycast()", mProfiler);
TriangleOverlapCallback triangleCallback(ray, proxyShape, raycastInfo, *this);
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
triangleCallback.setProfiler(mProfiler);
#endif
// Compute the AABB for the ray
const Vector3 rayEnd = ray.point1 + ray.maxFraction * (ray.point2 - ray.point1);
const AABB rayAABB(Vector3::min(ray.point1, rayEnd), Vector3::max(ray.point1, rayEnd));
@ -264,6 +271,13 @@ void TriangleOverlapCallback::testTriangle(uint meshSubPart, uint triangleIndex,
verticesNormals, meshSubPart, triangleIndex);
triangleShape.setRaycastTestType(mHeightFieldShape.getRaycastTestType());
#ifdef IS_PROFILING_ACTIVE
// Set the profiler to the triangle shape
triangleShape.setProfiler(mProfiler);
#endif
// Ray casting test against the collision shape
RaycastInfo raycastInfo;
bool isTriangleHit = triangleShape.raycast(mRay, raycastInfo, mProxyShape);

View File

@ -49,6 +49,13 @@ class TriangleOverlapCallback : public TriangleCallback {
bool mIsHit;
decimal mSmallestHitFraction;
const HeightFieldShape& mHeightFieldShape;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
public:
@ -66,6 +73,16 @@ class TriangleOverlapCallback : public TriangleCallback {
/// Raycast test between a ray and a triangle of the heightfield
virtual void testTriangle(uint meshSubPart, uint triangleIndex,
const Vector3* trianglePoints, const Vector3* verticesNormals) override;
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
};

View File

@ -153,13 +153,12 @@ Vector3 TriangleShape::computeSmoothLocalContactNormalForTriangle(const Vector3&
return (u * mVerticesNormals[0] + v * mVerticesNormals[1] + w * mVerticesNormals[2]).getUnit();
}
// Raycast method with feedback information
/// This method use the line vs triangle raycasting technique described in
/// Real-time Collision Detection by Christer Ericson.
bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
PROFILE("TriangleShape::raycast()");
PROFILE("TriangleShape::raycast()", mProfiler);
const Vector3 pq = ray.point2 - ray.point1;
const Vector3 pa = mPoints[0] - ray.point1;

View File

@ -37,6 +37,13 @@ CollisionWorld::CollisionWorld()
mCollisionDetection(this, mPoolAllocator, mSingleFrameAllocator), mCurrentBodyID(0),
mEventListener(nullptr) {
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
mCollisionDetection.setProfiler(&mProfiler);
#endif
}
// Destructor
@ -75,6 +82,12 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) {
// Add the collision body to the world
mBodies.insert(collisionBody);
#ifdef IS_PROFILING_ACTIVE
collisionBody->setProfiler(&mProfiler);
#endif
// Return the pointer to the rigid body
return collisionBody;
}

View File

@ -82,6 +82,12 @@ class CollisionWorld {
/// Pointer to an event listener object
EventListener* mEventListener;
#ifdef IS_PROFILING_ACTIVE
/// Real-time hierarchical profiler
Profiler mProfiler;
#endif
// -------------------- Methods -------------------- //
/// Return the next available body ID
@ -147,6 +153,12 @@ class CollisionWorld {
/// Test and report collisions between all shapes of the world
void testCollision(CollisionCallback* callback);
#ifdef IS_PROFILING_ACTIVE
/// Set the name of the profiler
void setProfilerName(std::string name);
#endif
/// Return the current world-space AABB of given proxy shape
AABB getWorldAABB(const ProxyShape* proxyShape) const;
@ -236,6 +248,15 @@ inline void CollisionWorld::testOverlap(CollisionBody* body, OverlapCallback* ov
mCollisionDetection.testOverlap(body, overlapCallback, categoryMaskBits);
}
#ifdef IS_PROFILING_ACTIVE
// Set the name of the profiler
inline void CollisionWorld::setProfilerName(std::string name) {
mProfiler.setName(name);
}
#endif
}
#endif

View File

@ -34,12 +34,18 @@ ConstraintSolver::ConstraintSolver(const std::map<RigidBody*, uint>& mapBodyToVe
: mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex),
mIsWarmStartingActive(true), mConstraintSolverData(mapBodyToVelocityIndex) {
#ifdef IS_PROFILING_ACTIVE
mProfiler = nullptr;
#endif
}
// Initialize the constraint solver for a given island
void ConstraintSolver::initializeForIsland(decimal dt, Island* island) {
PROFILE("ConstraintSolver::initializeForIsland()");
PROFILE("ConstraintSolver::initializeForIsland()", mProfiler);
assert(island != nullptr);
assert(island->getNbBodies() > 0);
@ -69,7 +75,7 @@ void ConstraintSolver::initializeForIsland(decimal dt, Island* island) {
// Solve the velocity constraints
void ConstraintSolver::solveVelocityConstraints(Island* island) {
PROFILE("ConstraintSolver::solveVelocityConstraints()");
PROFILE("ConstraintSolver::solveVelocityConstraints()", mProfiler);
assert(island != nullptr);
assert(island->getNbJoints() > 0);
@ -86,7 +92,7 @@ void ConstraintSolver::solveVelocityConstraints(Island* island) {
// Solve the position constraints
void ConstraintSolver::solvePositionConstraints(Island* island) {
PROFILE("ConstraintSolver::solvePositionConstraints()");
PROFILE("ConstraintSolver::solvePositionConstraints()", mProfiler);
assert(island != nullptr);
assert(island->getNbJoints() > 0);

View File

@ -165,6 +165,12 @@ class ConstraintSolver {
/// Constraint solver data used to initialize and solve the constraints
ConstraintSolverData mConstraintSolverData;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
public :
// -------------------- Methods -------------------- //
@ -197,6 +203,14 @@ class ConstraintSolver {
/// Set the constrained positions/orientations arrays
void setConstrainedPositionsArrays(Vector3* constrainedPositions,
Quaternion* constrainedOrientations);
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler);
#endif
};
// Set the constrained velocities arrays
@ -221,6 +235,15 @@ inline void ConstraintSolver::setConstrainedPositionsArrays(Vector3* constrained
mConstraintSolverData.orientations = constrainedOrientations;
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void ConstraintSolver::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
}
#endif

View File

@ -52,7 +52,7 @@ ContactSolver::ContactSolver(const std::map<RigidBody*, uint>& mapBodyToVelocity
// Initialize the contact constraints
void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) {
PROFILE("ContactSolver::init()");
PROFILE("ContactSolver::init()", mProfiler);
mTimeStep = timeStep;
@ -98,7 +98,7 @@ void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) {
// Initialize the constraint solver for a given island
void ContactSolver::initializeForIsland(Island* island) {
PROFILE("ContactSolver::initializeForIsland()");
PROFILE("ContactSolver::initializeForIsland()", mProfiler);
assert(island != nullptr);
assert(island->getNbBodies() > 0);
@ -270,7 +270,7 @@ void ContactSolver::initializeForIsland(Island* island) {
/// the solution of the linear system
void ContactSolver::warmStart() {
PROFILE("ContactSolver::warmStart()");
PROFILE("ContactSolver::warmStart()", mProfiler);
uint contactPointIndex = 0;
@ -387,7 +387,7 @@ void ContactSolver::warmStart() {
// Solve the contacts
void ContactSolver::solve() {
PROFILE("ContactSolver::solve()");
PROFILE("ContactSolver::solve()", mProfiler);
decimal deltaLambda;
decimal lambdaTemp;
@ -586,7 +586,7 @@ void ContactSolver::solve() {
// warm start the solver at the next iteration
void ContactSolver::storeImpulses() {
PROFILE("ContactSolver::storeImpulses()");
PROFILE("ContactSolver::storeImpulses()", mProfiler);
uint contactPointIndex = 0;
@ -614,7 +614,7 @@ void ContactSolver::storeImpulses() {
void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity,
ContactManifoldSolver& contact) const {
PROFILE("ContactSolver::computeFrictionVectors()");
PROFILE("ContactSolver::computeFrictionVectors()", mProfiler);
assert(contact.normal.length() > decimal(0.0));

View File

@ -308,6 +308,13 @@ class ContactSolver {
/// True if the split impulse position correction is active
bool mIsSplitImpulseActive;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* mProfiler;
#endif
// -------------------- Methods -------------------- //
/// Compute the collision restitution factor from the restitution factor of each body
@ -367,6 +374,13 @@ class ContactSolver {
/// Activate or Deactivate the split impulses for contacts
void setIsSplitImpulseActive(bool isActive);
#ifdef IS_PROFILING_ACTIVE
/// Set the profiler
void setProfiler(Profiler* profiler);
#endif
};
// Set the split velocities arrays
@ -425,6 +439,16 @@ inline decimal ContactSolver::computeMixedRollingResistance(RigidBody* body1,
return decimal(0.5f) * (body1->getMaterial().getRollingResistance() + body2->getMaterial().getRollingResistance());
}
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
inline void ContactSolver::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
}
#endif

View File

@ -29,6 +29,7 @@
#include "constraint/SliderJoint.h"
#include "constraint/HingeJoint.h"
#include "constraint/FixedJoint.h"
#include <fstream>
// Namespaces
using namespace reactphysics3d;
@ -53,6 +54,14 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity)
mSleepAngularVelocity(DEFAULT_SLEEP_ANGULAR_VELOCITY),
mTimeBeforeSleep(DEFAULT_TIME_BEFORE_SLEEP) {
#ifdef IS_PROFILING_ACTIVE
// Set the profiler
mConstraintSolver.setProfiler(&mProfiler);
mContactSolver.setProfiler(&mProfiler);
#endif
}
// Destructor
@ -80,10 +89,10 @@ DynamicsWorld::~DynamicsWorld() {
#ifdef IS_PROFILING_ACTIVE
// Print the profiling report
Profiler::printReport(std::cout);
// Destroy the profiler (release the allocated memory)
Profiler::destroy();
ofstream myfile;
myfile.open(mProfiler.getName() + ".txt");
mProfiler.printReport(myfile);
myfile.close();
#endif
}
@ -96,10 +105,10 @@ void DynamicsWorld::update(decimal timeStep) {
#ifdef IS_PROFILING_ACTIVE
// Increment the frame counter of the profiler
Profiler::incrementFrameCounter();
mProfiler.incrementFrameCounter();
#endif
PROFILE("DynamicsWorld::update()");
PROFILE("DynamicsWorld::update()", &mProfiler);
mTimeStep = timeStep;
@ -147,7 +156,7 @@ void DynamicsWorld::update(decimal timeStep) {
/// the sympletic Euler time stepping scheme.
void DynamicsWorld::integrateRigidBodiesPositions() {
PROFILE("DynamicsWorld::integrateRigidBodiesPositions()");
PROFILE("DynamicsWorld::integrateRigidBodiesPositions()", &mProfiler);
// For each island of the world
for (uint i=0; i < mNbIslands; i++) {
@ -186,7 +195,7 @@ void DynamicsWorld::integrateRigidBodiesPositions() {
// Update the postion/orientation of the bodies
void DynamicsWorld::updateBodiesState() {
PROFILE("DynamicsWorld::updateBodiesState()");
PROFILE("DynamicsWorld::updateBodiesState()", &mProfiler);
// For each island of the world
for (uint islandIndex = 0; islandIndex < mNbIslands; islandIndex++) {
@ -223,7 +232,7 @@ void DynamicsWorld::updateBodiesState() {
// Initialize the bodies velocities arrays for the next simulation step.
void DynamicsWorld::initVelocityArrays() {
PROFILE("DynamicsWorld::initVelocityArrays()");
PROFILE("DynamicsWorld::initVelocityArrays()", &mProfiler);
// Allocate memory for the bodies velocity arrays
uint nbBodies = mRigidBodies.size();
@ -266,7 +275,7 @@ void DynamicsWorld::initVelocityArrays() {
/// contact solver.
void DynamicsWorld::integrateRigidBodiesVelocities() {
PROFILE("DynamicsWorld::integrateRigidBodiesVelocities()");
PROFILE("DynamicsWorld::integrateRigidBodiesVelocities()", &mProfiler);
// Initialize the bodies velocity arrays
initVelocityArrays();
@ -328,7 +337,7 @@ void DynamicsWorld::integrateRigidBodiesVelocities() {
// Solve the contacts and constraints
void DynamicsWorld::solveContactsAndConstraints() {
PROFILE("DynamicsWorld::solveContactsAndConstraints()");
PROFILE("DynamicsWorld::solveContactsAndConstraints()", &mProfiler);
// Set the velocities arrays
mContactSolver.setSplitVelocitiesArrays(mSplitLinearVelocities, mSplitAngularVelocities);
@ -401,7 +410,7 @@ void DynamicsWorld::solveContactsAndConstraints() {
// Solve the position error correction of the constraints
void DynamicsWorld::solvePositionCorrection() {
PROFILE("DynamicsWorld::solvePositionCorrection()");
PROFILE("DynamicsWorld::solvePositionCorrection()", &mProfiler);
// Do not continue if there is no constraints
if (mJoints.empty()) return;
@ -442,6 +451,12 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) {
mBodies.insert(rigidBody);
mRigidBodies.insert(rigidBody);
#ifdef IS_PROFILING_ACTIVE
rigidBody->setProfiler(&mProfiler);
#endif
// Return the pointer to the rigid body
return rigidBody;
}
@ -613,7 +628,7 @@ void DynamicsWorld::addJointToBody(Joint* joint) {
/// it). Then, we create an island with this group of connected bodies.
void DynamicsWorld::computeIslands() {
PROFILE("DynamicsWorld::computeIslands()");
PROFILE("DynamicsWorld::computeIslands()", &mProfiler);
uint nbBodies = mRigidBodies.size();
@ -757,7 +772,7 @@ void DynamicsWorld::computeIslands() {
/// time, we put all the bodies of the island to sleep.
void DynamicsWorld::updateSleepingBodies() {
PROFILE("DynamicsWorld::updateSleepingBodies()");
PROFILE("DynamicsWorld::updateSleepingBodies()", &mProfiler);
const decimal sleepLinearVelocitySquare = mSleepLinearVelocity * mSleepLinearVelocity;
const decimal sleepAngularVelocitySquare = mSleepAngularVelocity * mSleepAngularVelocity;

View File

@ -124,19 +124,9 @@ class DynamicsWorld : public CollisionWorld {
/// Integrate the positions and orientations of rigid bodies.
void integrateRigidBodiesPositions();
/// Update the AABBs of the bodies
void updateRigidBodiesAABB();
/// Reset the external force and torque applied to the bodies
void resetBodiesForceAndTorque();
/// Update the position and orientation of a body
void updatePositionAndOrientationOfBody(RigidBody* body, Vector3 newLinVelocity,
Vector3 newAngVelocity);
/// Compute and set the interpolation factor to all bodies
void setInterpolationFactorToAllBodies();
/// Initialize the bodies velocities arrays for the next simulation step.
void initVelocityArrays();
@ -149,9 +139,6 @@ class DynamicsWorld : public CollisionWorld {
/// Solve the position error correction of the constraints
void solvePositionCorrection();
/// Cleanup the constrained velocities array at each step
void cleanupConstrainedVelocitiesArray();
/// Compute the islands of awake bodies.
void computeIslands();
@ -478,7 +465,6 @@ inline void DynamicsWorld::setEventListener(EventListener* eventListener) {
mEventListener = eventListener;
}
}
#endif

View File

@ -27,14 +27,12 @@
// Libraries
#include "Profiler.h"
#include <string>
using namespace reactphysics3d;
// Initialization of static variables
ProfileNode Profiler::mRootNode("Root", nullptr);
ProfileNode* Profiler::mCurrentNode = &Profiler::mRootNode;
long double Profiler::mProfilingStartTime = Timer::getCurrentSystemTime() * 1000.0;
uint Profiler::mFrameCounter = 0;
int Profiler::mNbProfilers = 0;
// Constructor
ProfileNode::ProfileNode(const char* name, ProfileNode* parentNode)
@ -157,6 +155,35 @@ void ProfileNodeIterator::enterParent() {
mCurrentChildNode = mCurrentParentNode->getChildNode();
}
// Constructor
Profiler::Profiler(std::string name) :mRootNode("Root", nullptr) {
// Set the name of the profiler
if (name == "") {
if (mNbProfilers == 0) {
mName = "profiler";
}
else {
mName = std::string("profiler") + std::to_string(mNbProfilers);
}
}
else {
mName = name;
}
mCurrentNode = &mRootNode;
mProfilingStartTime = Timer::getCurrentSystemTime() * 1000.0;
mFrameCounter = 0;
mNbProfilers++;
}
// Destructor
Profiler::~Profiler() {
destroy();
}
// Method called when we want to start profiling a block of code.
void Profiler::startProfilingBlock(const char* name) {

View File

@ -184,57 +184,73 @@ class Profiler {
// -------------------- Attributes -------------------- //
/// Profiler name
std::string mName;
/// Total number of profilers
static int mNbProfilers;
/// Root node of the profiler tree
static ProfileNode mRootNode;
ProfileNode mRootNode;
/// Current node in the current execution
static ProfileNode* mCurrentNode;
ProfileNode* mCurrentNode;
/// Frame counter
static uint mFrameCounter;
uint mFrameCounter;
/// Starting profiling time
static long double mProfilingStartTime;
long double mProfilingStartTime;
/// Recursively print the report of a given node of the profiler tree
static void printRecursiveNodeReport(ProfileNodeIterator* iterator,
int spacing,
std::ostream& outputStream);
void printRecursiveNodeReport(ProfileNodeIterator* iterator, int spacing, std::ostream& outputStream);
/// Destroy a previously allocated iterator
void destroyIterator(ProfileNodeIterator* iterator);
/// Destroy the profiler (release the memory)
void destroy();
public :
// -------------------- Methods -------------------- //
/// Constructor
Profiler(std::string name = "");
/// Destructor
~Profiler();
/// Method called when we want to start profiling a block of code.
static void startProfilingBlock(const char *name);
void startProfilingBlock(const char *name);
/// Method called at the end of the scope where the
/// startProfilingBlock() method has been called.
static void stopProfilingBlock();
void stopProfilingBlock();
/// Reset the timing data of the profiler (but not the profiler tree structure)
static void reset();
void reset();
/// Return the number of frames
static uint getNbFrames();
uint getNbFrames();
/// Get the name of the profiler
std::string getName() const;
/// Set the name of the profiler
void setName(std::string name);
/// Return the elasped time since the start/reset of the profiling
static long double getElapsedTimeSinceStart();
long double getElapsedTimeSinceStart();
/// Increment the frame counter
static void incrementFrameCounter();
void incrementFrameCounter();
/// Return an iterator over the profiler tree starting at the root
static ProfileNodeIterator* getIterator();
ProfileNodeIterator* getIterator();
/// Print the report of the profiler in a given output stream
static void printReport(std::ostream& outputStream);
/// Destroy a previously allocated iterator
static void destroyIterator(ProfileNodeIterator* iterator);
/// Destroy the profiler (release the memory)
static void destroy();
void printReport(std::ostream& outputStream);
};
// Class ProfileSample
@ -245,27 +261,33 @@ class Profiler {
*/
class ProfileSample {
private:
Profiler* mProfiler;
public :
// -------------------- Methods -------------------- //
/// Constructor
ProfileSample(const char* name) {
ProfileSample(const char* name, Profiler* profiler) :mProfiler(profiler) {
assert(profiler != nullptr);
// Ask the profiler to start profiling a block of code
Profiler::startProfilingBlock(name);
mProfiler->startProfilingBlock(name);
}
/// Destructor
~ProfileSample() {
// Tell the profiler to stop profiling a block of code
Profiler::stopProfilingBlock();
mProfiler->stopProfilingBlock();
}
};
// Use this macro to start profile a block of code
#define PROFILE(name) ProfileSample profileSample(name)
#define PROFILE(name, profiler) ProfileSample profileSample(name, profiler)
// Return true if we are at the root of the profiler tree
inline bool ProfileNodeIterator::isRoot() {
@ -352,6 +374,16 @@ inline uint Profiler::getNbFrames() {
return mFrameCounter;
}
// Get the name of the profiler
inline std::string Profiler::getName() const {
return mName;
}
// Set the name of the profiler
inline void Profiler::setName(std::string name) {
mName = name;
}
// Return the elasped time since the start/reset of the profiling
inline long double Profiler::getElapsedTimeSinceStart() {
long double currentTime = Timer::getCurrentSystemTime() * 1000.0;

View File

@ -49,6 +49,12 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// Create the dynamics world for the physics simulation
mPhysicsWorld = new rp3d::CollisionWorld();
#ifdef IS_PROFILING_ACTIVE
mPhysicsWorld->setProfilerName(name + "_profiler");
#endif
// ---------- Sphere 1 ---------- //
// Create a sphere and a corresponding collision body in the dynamics world
@ -72,6 +78,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
mSphere2->setSleepingColor(mRedColorDemo);
mPhysicsObjects.push_back(mSphere2);
// ---------- Capsule 1 ---------- //
// Create a cylinder and a corresponding collision body in the dynamics world
@ -94,49 +101,49 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
mCapsule2->setSleepingColor(mRedColorDemo);
mPhysicsObjects.push_back(mCapsule2);
// ---------- Concave Mesh ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world
mConcaveMesh = new ConcaveMesh(mPhysicsWorld, mMeshFolderPath + "city.obj");
mAllShapes.push_back(mConcaveMesh);
// Set the color
mConcaveMesh->setColor(mGreyColorDemo);
mConcaveMesh->setSleepingColor(mRedColorDemo);
mPhysicsObjects.push_back(mConcaveMesh);
// ---------- Box 1 ---------- //
// Create a cylinder and a corresponding collision body in the dynamics world
// Create a cylinder and a corresponding collision body in the dynamics world
mBox1 = new Box(BOX_SIZE, mPhysicsWorld, mMeshFolderPath);
mAllShapes.push_back(mBox1);
mAllShapes.push_back(mBox1);
// Set the color
mBox1->setColor(mGreyColorDemo);
mBox1->setSleepingColor(mRedColorDemo);
mPhysicsObjects.push_back(mBox1);
// Set the color
mBox1->setColor(mGreyColorDemo);
mBox1->setSleepingColor(mRedColorDemo);
mPhysicsObjects.push_back(mBox1);
// ---------- Box 2 ---------- //
// ---------- Box 2 ---------- //
// Create a cylinder and a corresponding collision body in the dynamics world
// Create a cylinder and a corresponding collision body in the dynamics world
mBox2 = new Box(openglframework::Vector3(3, 2, 5), mPhysicsWorld, mMeshFolderPath);
mAllShapes.push_back(mBox2);
mAllShapes.push_back(mBox2);
// Set the color
mBox2->setColor(mGreyColorDemo);
mBox2->setSleepingColor(mRedColorDemo);
mPhysicsObjects.push_back(mBox2);
// Set the color
mBox2->setColor(mGreyColorDemo);
mBox2->setSleepingColor(mRedColorDemo);
mPhysicsObjects.push_back(mBox2);
// ---------- Convex Mesh ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world
mConvexMesh = new ConvexMesh(mPhysicsWorld, mMeshFolderPath + "convexmesh.obj");
mAllShapes.push_back(mConvexMesh);
mAllShapes.push_back(mConvexMesh);
// Set the color
mConvexMesh->setColor(mGreyColorDemo);
mConvexMesh->setSleepingColor(mRedColorDemo);
mPhysicsObjects.push_back(mConvexMesh);
// ---------- Concave Mesh ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world
mConcaveMesh = new ConcaveMesh(mPhysicsWorld, mMeshFolderPath + "city.obj");
mAllShapes.push_back(mConcaveMesh);
// Set the color
mConcaveMesh->setColor(mGreyColorDemo);
mConcaveMesh->setSleepingColor(mRedColorDemo);
mPhysicsObjects.push_back(mConcaveMesh);
mPhysicsObjects.push_back(mConvexMesh);
// ---------- Heightfield ---------- //
@ -154,14 +161,14 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine
// Reset the scene
void CollisionDetectionScene::reset() {
mSphere1->setTransform(rp3d::Transform(rp3d::Vector3(12, 0, 0), rp3d::Quaternion::identity()));
mSphere2->setTransform(rp3d::Transform(rp3d::Vector3(12, 8, 0), rp3d::Quaternion::identity()));
mCapsule1->setTransform(rp3d::Transform(rp3d::Vector3(-6, 7, 0), rp3d::Quaternion::identity()));
mSphere1->setTransform(rp3d::Transform(rp3d::Vector3(15, 5, 0), rp3d::Quaternion::identity()));
mSphere2->setTransform(rp3d::Transform(rp3d::Vector3(0, 6, 0), rp3d::Quaternion::identity()));
mCapsule1->setTransform(rp3d::Transform(rp3d::Vector3(-8, 7, 0), rp3d::Quaternion::identity()));
mCapsule2->setTransform(rp3d::Transform(rp3d::Vector3(11, -8, 0), rp3d::Quaternion::identity()));
mBox1->setTransform(rp3d::Transform(rp3d::Vector3(-4, -7, 0), rp3d::Quaternion::identity()));
mBox2->setTransform(rp3d::Transform(rp3d::Vector3(0, 8, 0), rp3d::Quaternion::identity()));
mBox2->setTransform(rp3d::Transform(rp3d::Vector3(0, 9, 0), rp3d::Quaternion::identity()));
mConvexMesh->setTransform(rp3d::Transform(rp3d::Vector3(-5, 0, 0), rp3d::Quaternion::identity()));
mConcaveMesh->setTransform(rp3d::Transform(rp3d::Vector3(0, 100, 0), rp3d::Quaternion::identity()));
mConcaveMesh->setTransform(rp3d::Transform(rp3d::Vector3(0, 0, 0), rp3d::Quaternion::identity()));
mHeightField->setTransform(rp3d::Transform(rp3d::Vector3(0, -12, 0), rp3d::Quaternion::identity()));
}

View File

@ -152,7 +152,7 @@ class CollisionDetectionScene : public SceneDemo {
std::vector<PhysicsObject*> mAllShapes;
uint mSelectedShapeIndex;
unsigned int mSelectedShapeIndex;
/// Select the next shape
void selectNextShape();

View File

@ -46,7 +46,14 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin
rp3d::Vector3 gravity(0, -9.81f, 0);
// Create the dynamics world for the physics simulation
mPhysicsWorld = new rp3d::DynamicsWorld(gravity);
mPhysicsWorld = new rp3d::DynamicsWorld(gravity);
#ifdef IS_PROFILING_ACTIVE
mPhysicsWorld->setProfilerName(name + "_profiler");
#endif
for (int i=0; i<NB_COMPOUND_SHAPES; i++) {

View File

@ -48,6 +48,13 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& sett
// Create the dynamics world for the physics simulation
mPhysicsWorld = new rp3d::DynamicsWorld(gravity);
#ifdef IS_PROFILING_ACTIVE
mPhysicsWorld->setProfilerName(name + "_profiler");
#endif
// ---------- Create the boxes ----------- //
for (int i = 0; i<NB_COMPOUND_SHAPES; i++) {
// Create a convex mesh and a corresponding rigid in the dynamics world

6
testbed/scenes/cubes/CubesScene.cpp Executable file → Normal file
View File

@ -46,6 +46,12 @@ CubesScene::CubesScene(const std::string& name, EngineSettings& settings)
// Create the dynamics world for the physics simulation
mPhysicsWorld = new rp3d::DynamicsWorld(gravity);
#ifdef IS_PROFILING_ACTIVE
mPhysicsWorld->setProfilerName(name + "_profiler");
#endif
// Create all the cubes of the scene
for (int i=0; i<NB_CUBES; i++) {

View File

@ -46,7 +46,14 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett
rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0);
// Create the dynamics world for the physics simulation
mPhysicsWorld = new rp3d::DynamicsWorld(gravity);
mPhysicsWorld = new rp3d::DynamicsWorld(gravity);
#ifdef IS_PROFILING_ACTIVE
mPhysicsWorld->setProfilerName(name + "_profiler");
#endif
for (int i = 0; i<NB_COMPOUND_SHAPES; i++) {

View File

@ -47,6 +47,12 @@ JointsScene::JointsScene(const std::string& name, EngineSettings& settings)
// Create the dynamics world for the physics simulation
mPhysicsWorld = new rp3d::DynamicsWorld(gravity);
#ifdef IS_PROFILING_ACTIVE
mPhysicsWorld->setProfilerName(name + "_profiler");
#endif
// Create the Ball-and-Socket joint
createBallAndSocketJoints();

View File

@ -47,6 +47,12 @@ RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings)
// Create the dynamics world for the physics simulation
mPhysicsWorld = new rp3d::CollisionWorld();
#ifdef IS_PROFILING_ACTIVE
mPhysicsWorld->setProfilerName(name + "_profiler");
#endif
// ---------- Dumbbell ---------- //
// Create a convex mesh and a corresponding collision body in the dynamics world

View File

@ -53,8 +53,8 @@ struct EngineSettings {
long double elapsedTime; // Elapsed time (in seconds)
float timeStep; // Current time step (in seconds)
uint nbVelocitySolverIterations; // Nb of velocity solver iterations
uint nbPositionSolverIterations; // Nb of position solver iterations
unsigned int nbVelocitySolverIterations; // Nb of velocity solver iterations
unsigned int nbPositionSolverIterations; // Nb of position solver iterations
bool isSleepingEnabled; // True if sleeping technique is enabled
float timeBeforeSleep; // Time of inactivity before a body sleep
float sleepLinearVelocity; // Sleep linear velocity