Merge branch 'develop' of https://code.google.com/p/reactphysics3d into develop
This commit is contained in:
commit
db23fd0000
|
@ -76,7 +76,7 @@ struct ContactInfo {
|
|||
const Vector3& localPoint1, const Vector3& localPoint2);
|
||||
};
|
||||
|
||||
} // End of the ReactPhysics3D namespace
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -82,9 +82,7 @@ class NoBroadPhaseAlgorithm : public BroadPhaseAlgorithm {
|
|||
|
||||
// Notify the broad-phase about a new object in the world
|
||||
inline void NoBroadPhaseAlgorithm::addObject(CollisionBody* body, const AABB& aabb) {
|
||||
|
||||
std::cout << "New body in broadphase with id=" << body->getID() << std::endl;
|
||||
|
||||
|
||||
// For each body that is already in the world
|
||||
for (std::set<CollisionBody*>::iterator it = mBodies.begin(); it != mBodies.end(); ++it) {
|
||||
|
||||
|
|
|
@ -36,9 +36,9 @@ bodyindex PairManager::INVALID_INDEX = std::numeric_limits<reactphysics3d::bodyi
|
|||
// Constructor of PairManager
|
||||
PairManager::PairManager(CollisionDetection& collisionDetection)
|
||||
: mCollisionDetection(collisionDetection) {
|
||||
mHashTable = 0;
|
||||
mOverlappingPairs = 0;
|
||||
mOffsetNextPair = 0;
|
||||
mHashTable = NULL;
|
||||
mOverlappingPairs = NULL;
|
||||
mOffsetNextPair = NULL;
|
||||
mNbOverlappingPairs = 0;
|
||||
mHashMask = 0;
|
||||
mNbElementsHashTable = 0;
|
||||
|
@ -123,7 +123,7 @@ bool PairManager::removePair(bodyindex id1, bodyindex id2) {
|
|||
BodyPair* pair = findPairWithHashValue(id1, id2, hashValue);
|
||||
|
||||
// If we have not found the pair
|
||||
if (!pair) {
|
||||
if (pair == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -236,8 +236,7 @@ BodyPair* PairManager::lookForAPair(bodyindex id1, bodyindex id2, luint hashValu
|
|||
|
||||
// If the pair has not been found in the overlapping pairs
|
||||
if (offset == INVALID_INDEX) {
|
||||
// Return null
|
||||
return 0;
|
||||
return NULL;
|
||||
}
|
||||
|
||||
assert(offset < mNbOverlappingPairs);
|
||||
|
@ -253,7 +252,7 @@ void PairManager::reallocatePairs() {
|
|||
// Reallocate the hash table and initialize it
|
||||
free(mHashTable);
|
||||
mHashTable = (bodyindex*) malloc(mNbElementsHashTable * sizeof(bodyindex));
|
||||
assert(mHashTable);
|
||||
assert(mHashTable != NULL);
|
||||
for (bodyindex i=0; i<mNbElementsHashTable; i++) {
|
||||
mHashTable[i] = INVALID_INDEX;
|
||||
}
|
||||
|
@ -262,8 +261,8 @@ void PairManager::reallocatePairs() {
|
|||
BodyPair* newOverlappingPairs = (BodyPair*) malloc(mNbElementsHashTable * sizeof(BodyPair));
|
||||
bodyindex* newOffsetNextPair = (bodyindex*) malloc(mNbElementsHashTable * sizeof(bodyindex));
|
||||
|
||||
assert(newOverlappingPairs);
|
||||
assert(newOffsetNextPair);
|
||||
assert(newOverlappingPairs != NULL);
|
||||
assert(newOffsetNextPair != NULL);
|
||||
|
||||
// If there is already some overlapping pairs
|
||||
if (mNbOverlappingPairs) {
|
||||
|
@ -286,5 +285,4 @@ void PairManager::reallocatePairs() {
|
|||
// Replace by the new data
|
||||
mOverlappingPairs = newOverlappingPairs;
|
||||
mOffsetNextPair = newOffsetNextPair;
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -260,7 +260,7 @@ inline int PairManager::computeHash32Bits(int key) const {
|
|||
inline BodyPair* PairManager::findPair(bodyindex id1, bodyindex id2) const {
|
||||
|
||||
// Check if the hash table has been allocated yet
|
||||
if (!mHashTable) return 0;
|
||||
if (mHashTable == NULL) return NULL;
|
||||
|
||||
// Sort the IDs
|
||||
sortIDs(id1, id2);
|
||||
|
@ -279,7 +279,7 @@ inline BodyPair* PairManager::findPairWithHashValue(bodyindex id1, bodyindex id2
|
|||
luint hashValue) const {
|
||||
|
||||
// Check if the hash table has been allocated yet
|
||||
if (!mHashTable) return 0;
|
||||
if (mHashTable == NULL) return NULL;
|
||||
|
||||
// Look for the pair in the set of overlapping pairs
|
||||
return lookForAPair(id1, id2, hashValue);
|
||||
|
|
|
@ -47,10 +47,10 @@ AABBInt::AABBInt(const AABB& aabb) {
|
|||
// Constructor
|
||||
SweepAndPruneAlgorithm::SweepAndPruneAlgorithm(CollisionDetection& collisionDetection)
|
||||
:BroadPhaseAlgorithm(collisionDetection) {
|
||||
mBoxes = 0;
|
||||
mEndPoints[0] = 0;
|
||||
mEndPoints[1] = 0;
|
||||
mEndPoints[2] = 0;
|
||||
mBoxes = NULL;
|
||||
mEndPoints[0] = NULL;
|
||||
mEndPoints[1] = NULL;
|
||||
mEndPoints[2] = NULL;
|
||||
mNbBoxes = 0;
|
||||
mNbMaxBoxes = 0;
|
||||
}
|
||||
|
@ -399,10 +399,10 @@ void SweepAndPruneAlgorithm::resizeArrays() {
|
|||
EndPoint* newEndPointsYArray = new EndPoint[newNbEndPoints];
|
||||
EndPoint* newEndPointsZArray = new EndPoint[newNbEndPoints];
|
||||
|
||||
assert(newBoxesArray);
|
||||
assert(newEndPointsXArray);
|
||||
assert(newEndPointsYArray);
|
||||
assert(newEndPointsZArray);
|
||||
assert(newBoxesArray != NULL);
|
||||
assert(newEndPointsXArray != NULL);
|
||||
assert(newEndPointsYArray != NULL);
|
||||
assert(newEndPointsZArray != NULL);
|
||||
|
||||
// If the arrays were not empty before
|
||||
if (mNbBoxes > 0) {
|
||||
|
|
|
@ -225,9 +225,9 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple
|
|||
TriangleEPA* face3 = triangleStore.newTriangle(points, 1, 3, 2);
|
||||
|
||||
// If the constructed tetrahedron is not correct
|
||||
if (!(face0 && face1 && face2 && face3 && face0->getDistSquare() > 0.0 &&
|
||||
face1->getDistSquare() > 0.0 && face2->getDistSquare() > 0.0 &&
|
||||
face3->getDistSquare() > 0.0)) {
|
||||
if (!((face0 != NULL) && (face1 != NULL) && (face2 != NULL) && (face3 != NULL)
|
||||
&& face0->getDistSquare() > 0.0 && face1->getDistSquare() > 0.0
|
||||
&& face2->getDistSquare() > 0.0 && face3->getDistSquare() > 0.0)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -250,6 +250,7 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple
|
|||
|
||||
// If the tetrahedron contains a wrong vertex (the origin is not inside the tetrahedron)
|
||||
if (badVertex < 4) {
|
||||
|
||||
// Replace the wrong vertex with the point 5 (if it exists)
|
||||
suppPointsA[badVertex-1] = suppPointsA[4];
|
||||
suppPointsB[badVertex-1] = suppPointsB[4];
|
||||
|
@ -290,7 +291,8 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple
|
|||
TriangleEPA* face5 = triangleStore.newTriangle(points, 1, 0, 4);
|
||||
|
||||
// If the polytope hasn't been correctly constructed
|
||||
if (!(face0 && face1 && face2 && face3 && face4 && face5 &&
|
||||
if (!((face0 != NULL) && (face1 != NULL) && (face2 != NULL) && (face3 != NULL)
|
||||
&& (face4 != NULL) && (face5 != NULL) &&
|
||||
face0->getDistSquare() > 0.0 && face1->getDistSquare() > 0.0 &&
|
||||
face2->getDistSquare() > 0.0 && face3->getDistSquare() > 0.0 &&
|
||||
face4->getDistSquare() > 0.0 && face5->getDistSquare() > 0.0)) {
|
||||
|
|
|
@ -70,6 +70,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex,
|
|||
TrianglesStore& triangleStore) {
|
||||
// If the edge has not already been visited
|
||||
if (!mOwnerTriangle->getIsObsolete()) {
|
||||
|
||||
// If the triangle of this edge is not visible from the given point
|
||||
if (!mOwnerTriangle->isVisibleFromVertex(vertices, indexNewVertex)) {
|
||||
TriangleEPA* triangle = triangleStore.newTriangle(vertices, indexNewVertex,
|
||||
|
@ -77,7 +78,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex,
|
|||
getSourceVertexIndex());
|
||||
|
||||
// If the triangle has been created
|
||||
if (triangle) {
|
||||
if (triangle != NULL) {
|
||||
halfLink(EdgeEPA(triangle, 1), *this);
|
||||
return true;
|
||||
}
|
||||
|
@ -85,6 +86,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex,
|
|||
return false;
|
||||
}
|
||||
else {
|
||||
|
||||
// The current triangle is visible and therefore obsolete
|
||||
mOwnerTriangle->setIsObsolete(true);
|
||||
|
||||
|
@ -101,7 +103,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex,
|
|||
getSourceVertexIndex());
|
||||
|
||||
// If the triangle has been created
|
||||
if (triangle) {
|
||||
if (triangle != NULL) {
|
||||
halfLink(EdgeEPA(triangle, 1), *this);
|
||||
return true;
|
||||
}
|
||||
|
@ -120,7 +122,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex,
|
|||
getTargetVertexIndex(),
|
||||
getSourceVertexIndex());
|
||||
|
||||
if (triangle) {
|
||||
if (triangle != NULL) {
|
||||
halfLink(EdgeEPA(triangle, 1), *this);
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -118,7 +118,7 @@ inline TriangleEPA& TrianglesStore::last() {
|
|||
// Create a new triangle
|
||||
inline TriangleEPA* TrianglesStore::newTriangle(const Vector3* vertices,
|
||||
uint v0,uint v1, uint v2) {
|
||||
TriangleEPA* newTriangle = 0;
|
||||
TriangleEPA* newTriangle = NULL;
|
||||
|
||||
// If we have not reached the maximum number of triangles
|
||||
if (mNbTriangles != MAX_TRIANGLES) {
|
||||
|
@ -126,7 +126,7 @@ inline TriangleEPA* TrianglesStore::newTriangle(const Vector3* vertices,
|
|||
new (newTriangle) TriangleEPA(v0, v1, v2);
|
||||
if (!newTriangle->computeClosestPoint(vertices)) {
|
||||
mNbTriangles--;
|
||||
newTriangle = 0;
|
||||
newTriangle = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -117,6 +117,7 @@ bool GJKAlgorithm::testCollision(const CollisionShape* collisionShape1,
|
|||
|
||||
// If the objects intersect only in the margins
|
||||
if (simplex.isPointInSimplex(w) || distSquare - vDotw <= distSquare * REL_ERROR_SQUARE) {
|
||||
|
||||
// Compute the closet points of both objects (without the margins)
|
||||
simplex.computeClosestPointsOfAandB(pA, pB);
|
||||
|
||||
|
@ -148,6 +149,7 @@ bool GJKAlgorithm::testCollision(const CollisionShape* collisionShape1,
|
|||
|
||||
// If the simplex is affinely dependent
|
||||
if (simplex.isAffinelyDependent()) {
|
||||
|
||||
// Compute the closet points of both objects (without the margins)
|
||||
simplex.computeClosestPointsOfAandB(pA, pB);
|
||||
|
||||
|
@ -177,6 +179,7 @@ bool GJKAlgorithm::testCollision(const CollisionShape* collisionShape1,
|
|||
// Compute the point of the simplex closest to the origin
|
||||
// If the computation of the closest point fail
|
||||
if (!simplex.computeClosestPoint(v)) {
|
||||
|
||||
// Compute the closet points of both objects (without the margins)
|
||||
simplex.computeClosestPointsOfAandB(pA, pB);
|
||||
|
||||
|
@ -290,6 +293,7 @@ bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShap
|
|||
|
||||
// If the enlarge objects do not intersect
|
||||
if (vDotw > 0.0) {
|
||||
|
||||
// No intersection, we return false
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -120,8 +120,10 @@ unsigned int Simplex::getSimplex(Vector3* suppPointsA, Vector3* suppPointsB,
|
|||
|
||||
// For each four point in the possible simplex
|
||||
for (i=0, bit=0x1; i<4; i++, bit <<=1) {
|
||||
|
||||
// If the current point is in the simplex
|
||||
if (overlap(mBitsCurrentSimplex, bit)) {
|
||||
|
||||
// Store the points
|
||||
suppPointsA[nbVertices] = this->mSuppPointsA[nbVertices];
|
||||
suppPointsB[nbVertices] = this->mSuppPointsB[nbVertices];
|
||||
|
|
|
@ -31,7 +31,7 @@ using namespace reactphysics3d;
|
|||
|
||||
// Constructor
|
||||
NarrowPhaseAlgorithm::NarrowPhaseAlgorithm(MemoryPool<ContactInfo>& memoryPool)
|
||||
:mMemoryPoolContactInfos(memoryPool), mCurrentOverlappingPair(0) {
|
||||
:mMemoryPoolContactInfos(memoryPool), mCurrentOverlappingPair(NULL) {
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -45,7 +45,7 @@ using namespace reactphysics3d;
|
|||
using namespace std;
|
||||
|
||||
// Constructor
|
||||
AABB::AABB() : mBodyPointer(0) {
|
||||
AABB::AABB() : mBodyPointer(NULL) {
|
||||
|
||||
}
|
||||
|
||||
|
@ -56,7 +56,7 @@ AABB::AABB(const Vector3& minCoordinates, const Vector3& maxCoordinates, Body* m
|
|||
}
|
||||
|
||||
// Constructor
|
||||
AABB::AABB(const Transform& transform, const Vector3& extents) : mBodyPointer(0) {
|
||||
AABB::AABB(const Transform& transform, const Vector3& extents) : mBodyPointer(NULL) {
|
||||
update(transform, extents);
|
||||
}
|
||||
|
||||
|
|
|
@ -158,6 +158,6 @@ inline void AABB::update(const Transform& newTransform, const Vector3& extents)
|
|||
mMaxCoordinates = newTransform.getPosition() + worldExtents;
|
||||
}
|
||||
|
||||
}; // End of the ReactPhysics3D namespace
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -112,10 +112,10 @@ inline Vector3 BoxShape::getLocalSupportPoint(const Vector3& direction, decimal
|
|||
assert(margin >= 0.0);
|
||||
|
||||
return Vector3(direction.x < 0.0 ? -mExtent.x - margin : mExtent.x + margin,
|
||||
direction.y < 0.0 ? -mExtent.y - margin : mExtent.y + margin,
|
||||
direction.z < 0.0 ? -mExtent.z - margin : mExtent.z + margin);
|
||||
direction.y < 0.0 ? -mExtent.y - margin : mExtent.y + margin,
|
||||
direction.z < 0.0 ? -mExtent.z - margin : mExtent.z + margin);
|
||||
}
|
||||
|
||||
}; // End of the ReactPhysics3D namespace
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -143,6 +143,6 @@ inline void ConeShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass
|
|||
0.0, 0.0, 0.0, diagXZ);
|
||||
}
|
||||
|
||||
}; // End of the ReactPhysics3D namespace
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -133,7 +133,7 @@ inline void CylinderShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal
|
|||
0.0, 0.0, diag);
|
||||
}
|
||||
|
||||
}; // End of the ReactPhysics3D namespace
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -127,6 +127,6 @@ inline void SphereShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal ma
|
|||
0.0, 0.0, diag);
|
||||
}
|
||||
|
||||
}; // End of the ReactPhysics3D namespace
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -148,8 +148,6 @@ inline void Constraint::setCachedLambda(int index, decimal lambda) {
|
|||
mCachedLambdas[index] = lambda;
|
||||
}
|
||||
|
||||
|
||||
|
||||
} // End of the ReactPhysics3D namespace
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -78,6 +78,8 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform,
|
|||
CollisionBody* collisionBody = new (mMemoryPoolCollisionBodies.allocateObject())
|
||||
CollisionBody(transform, collisionShape, bodyID);
|
||||
|
||||
assert(collisionBody != NULL);
|
||||
|
||||
// Add the collision body to the world
|
||||
mBodies.insert(collisionBody);
|
||||
|
||||
|
|
|
@ -149,6 +149,7 @@ int ContactManifold::getIndexOfDeepestPenetration(ContactPoint* newContact) cons
|
|||
|
||||
// For each contact in the cache
|
||||
for (uint i=0; i<mNbContactPoints; i++) {
|
||||
|
||||
// If the current contact has a larger penetration depth
|
||||
if (mContactPoints[i]->getPenetrationDepth() > maxPenetrationDepth) {
|
||||
maxPenetrationDepth = mContactPoints[i]->getPenetrationDepth();
|
||||
|
|
|
@ -111,7 +111,7 @@ void DynamicsWorld::updateRigidBodiesPositionAndOrientation() {
|
|||
for (set<RigidBody*>::iterator it=getRigidBodiesBeginIterator(); it != getRigidBodiesEndIterator(); ++it) {
|
||||
|
||||
RigidBody* rigidBody = *it;
|
||||
assert(rigidBody);
|
||||
assert(rigidBody != NULL);
|
||||
|
||||
// If the body is allowed to move
|
||||
if (rigidBody->getIsMotionEnabled()) {
|
||||
|
@ -214,10 +214,11 @@ void DynamicsWorld::applyGravity() {
|
|||
for (set<RigidBody*>::iterator it=getRigidBodiesBeginIterator(); it != getRigidBodiesEndIterator(); ++it) {
|
||||
|
||||
RigidBody* rigidBody = dynamic_cast<RigidBody*>(*it);
|
||||
assert(rigidBody);
|
||||
assert(rigidBody != NULL);
|
||||
|
||||
// If the gravity force is on
|
||||
if(mIsGravityOn) {
|
||||
|
||||
// Apply the current gravity force to the body
|
||||
rigidBody->setExternalForce(rigidBody->getMass() * mGravity);
|
||||
}
|
||||
|
@ -237,6 +238,7 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform, decimal ma
|
|||
|
||||
// Create the rigid body
|
||||
RigidBody* rigidBody = new (mMemoryPoolRigidBodies.allocateObject()) RigidBody(transform, mass, inertiaTensorLocal, collisionShape, bodyID);
|
||||
assert(rigidBody != NULL);
|
||||
|
||||
// Add the rigid body to the physics world
|
||||
mBodies.insert(rigidBody);
|
||||
|
@ -282,8 +284,8 @@ void DynamicsWorld::notifyAddedOverlappingPair(const BroadPhasePair* addedPair)
|
|||
|
||||
// Add the pair into the set of overlapping pairs (if not there yet)
|
||||
OverlappingPair* newPair = new (mMemoryPoolOverlappingPairs.allocateObject()) OverlappingPair(addedPair->body1, addedPair->body2, mMemoryPoolContacts);
|
||||
assert(newPair != NULL);
|
||||
std::pair<map<std::pair<bodyindex, bodyindex>, OverlappingPair*>::iterator, bool> check = mOverlappingPairs.insert(make_pair(indexPair, newPair));
|
||||
assert(check.second);
|
||||
}
|
||||
|
||||
// Notify the world about a removed broad-phase overlapping pair
|
||||
|
@ -304,35 +306,21 @@ void DynamicsWorld::notifyNewContact(const BroadPhasePair* broadPhasePair, const
|
|||
RigidBody* const rigidBody1 = dynamic_cast<RigidBody* const>(broadPhasePair->body1);
|
||||
RigidBody* const rigidBody2 = dynamic_cast<RigidBody* const>(broadPhasePair->body2);
|
||||
|
||||
assert(rigidBody1);
|
||||
assert(rigidBody2);
|
||||
assert(rigidBody1 != NULL);
|
||||
assert(rigidBody2 != NULL);
|
||||
|
||||
// Create a new contact
|
||||
ContactPoint* contact = new (mMemoryPoolContacts.allocateObject()) ContactPoint(rigidBody1, rigidBody2, contactInfo);
|
||||
assert(contact);
|
||||
assert(contact != NULL);
|
||||
|
||||
// Get the corresponding overlapping pair
|
||||
pair<bodyindex, bodyindex> indexPair = broadPhasePair->getBodiesIndexPair();
|
||||
OverlappingPair* overlappingPair = mOverlappingPairs[indexPair];
|
||||
assert(overlappingPair);
|
||||
assert(overlappingPair != NULL);
|
||||
|
||||
// Add the contact to the contact cache of the corresponding overlapping pair
|
||||
overlappingPair->addContact(contact);
|
||||
|
||||
// TODO : Remove this
|
||||
/*
|
||||
// Create a contact manifold with the contact points of the two bodies
|
||||
ContactManifold contactManifold;
|
||||
contactManifold.nbContacts = 0;
|
||||
|
||||
// Add all the contacts in the contact cache of the two bodies
|
||||
// to the set of constraints in the physics world
|
||||
for (uint i=0; i<overlappingPair->getNbContacts(); i++) {
|
||||
contactManifold.contacts[i] = overlappingPair->getContact(i);
|
||||
contactManifold.nbContacts++;
|
||||
}
|
||||
*/
|
||||
|
||||
// Add the contact manifold to the world
|
||||
mContactManifolds.push_back(overlappingPair->getContactManifold());
|
||||
}
|
||||
|
|
|
@ -219,8 +219,6 @@ public :
|
|||
std::set<RigidBody*>::iterator getRigidBodiesEndIterator();
|
||||
};
|
||||
|
||||
// --- Inline functions --- //
|
||||
|
||||
// Start the physics simulation
|
||||
inline void DynamicsWorld::start() {
|
||||
mTimer.start();
|
||||
|
@ -283,7 +281,7 @@ inline void DynamicsWorld::addConstraint(Constraint* constraint) {
|
|||
inline void DynamicsWorld::removeConstraint(Constraint* constraint) {
|
||||
std::vector<Constraint*>::iterator it;
|
||||
|
||||
assert(constraint);
|
||||
assert(constraint != NULL);
|
||||
it = std::find(mConstraints.begin(), mConstraints.end(), constraint);
|
||||
assert(*it == constraint);
|
||||
delete *it;
|
||||
|
|
|
@ -97,14 +97,10 @@ class OverlappingPair {
|
|||
void setCachedSeparatingAxis(const Vector3& axis);
|
||||
|
||||
// Return the number of contacts in the cache
|
||||
uint getNbContacts() const;
|
||||
uint getNbContactPoints() const;
|
||||
|
||||
// Return the contact manifold
|
||||
ContactManifold* getContactManifold();
|
||||
|
||||
// Return a contact of the cache
|
||||
// TODO : Maybe remove this method
|
||||
ContactPoint* getContact(uint index) const;
|
||||
};
|
||||
|
||||
// Return the pointer to first body
|
||||
|
@ -120,26 +116,26 @@ inline CollisionBody* const OverlappingPair::getBody2() const {
|
|||
// Add a contact to the contact manifold
|
||||
inline void OverlappingPair::addContact(ContactPoint* contact) {
|
||||
mContactManifold.addContactPoint(contact);
|
||||
}
|
||||
}
|
||||
|
||||
// Update the contact manifold
|
||||
inline void OverlappingPair::update() {
|
||||
mContactManifold.update(mBody1->getTransform(), mBody2->getTransform());
|
||||
}
|
||||
}
|
||||
|
||||
// Return the cached separating axis
|
||||
inline Vector3 OverlappingPair::getCachedSeparatingAxis() const {
|
||||
return mCachedSeparatingAxis;
|
||||
}
|
||||
}
|
||||
|
||||
// Set the cached separating axis
|
||||
inline void OverlappingPair::setCachedSeparatingAxis(const Vector3& axis) {
|
||||
mCachedSeparatingAxis = axis;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Return the number of contacts in the cache
|
||||
inline uint OverlappingPair::getNbContacts() const {
|
||||
// Return the number of contact points in the contact manifold
|
||||
inline uint OverlappingPair::getNbContactPoints() const {
|
||||
return mContactManifold.getNbContactPoints();
|
||||
}
|
||||
|
||||
|
@ -148,11 +144,6 @@ inline ContactManifold* OverlappingPair::getContactManifold() {
|
|||
return &mContactManifold;
|
||||
}
|
||||
|
||||
// Return a contact of the cache
|
||||
inline ContactPoint* OverlappingPair::getContact(uint index) const {
|
||||
return mContactManifold.getContactPoint(index);
|
||||
}
|
||||
|
||||
} // End of the ReactPhysics3D namespace
|
||||
|
||||
#endif
|
||||
|
|
|
@ -131,9 +131,9 @@ template<class T> const uint MemoryPool<T>::NB_OBJECTS_FIRST_BLOCK = 100;
|
|||
template<class T>
|
||||
MemoryPool<T>::MemoryPool(uint capacity) throw(std::bad_alloc)
|
||||
: mCurrentNbObjects(0), mCapacity(capacity) {
|
||||
mPBlocks = 0;
|
||||
mPAllocatedUnits = 0;
|
||||
mPFreeUnits = 0;
|
||||
mPBlocks = NULL;
|
||||
mPAllocatedUnits = NULL;
|
||||
mPFreeUnits = NULL;
|
||||
mNbObjectsNextBlock = (capacity == 0) ? NB_OBJECTS_FIRST_BLOCK : capacity;
|
||||
|
||||
// Allocate the first memory block if the capacity is
|
||||
|
@ -172,12 +172,12 @@ void* MemoryPool<T>::allocateObject() {
|
|||
}
|
||||
|
||||
assert(mCurrentNbObjects < mCapacity);
|
||||
assert(mPFreeUnits);
|
||||
assert(mPFreeUnits != NULL);
|
||||
|
||||
MemoryUnit* currentUnit = mPFreeUnits;
|
||||
mPFreeUnits = currentUnit->pNext;
|
||||
if (mPFreeUnits) {
|
||||
mPFreeUnits->pPrevious = 0;
|
||||
mPFreeUnits->pPrevious = NULL;
|
||||
}
|
||||
|
||||
currentUnit->pNext = mPAllocatedUnits;
|
||||
|
@ -206,7 +206,7 @@ void MemoryPool<T>::freeObject(void* pObjectToFree) {
|
|||
MemoryUnit* currentUnit = (MemoryUnit*)((char*)pObjectToFree - sizeof(MemoryUnit));
|
||||
mPAllocatedUnits = currentUnit->pNext;
|
||||
if (mPAllocatedUnits) {
|
||||
mPAllocatedUnits->pPrevious = 0;
|
||||
mPAllocatedUnits->pPrevious = NULL;
|
||||
}
|
||||
|
||||
currentUnit->pNext = mPFreeUnits;
|
||||
|
@ -232,8 +232,8 @@ void MemoryPool<T>::allocateMemory() {
|
|||
// Allocate a new memory block
|
||||
mPBlocks = malloc(sizeBlock);
|
||||
|
||||
// Check that the allocation didn't fail
|
||||
if (!mPBlocks) throw std::bad_alloc();
|
||||
// Check that the allocation did not fail
|
||||
if (mPBlocks == NULL) throw std::bad_alloc();
|
||||
|
||||
MemoryBlock* block = (MemoryBlock*) mPBlocks;
|
||||
block->pNext = tempBlocks;
|
||||
|
@ -245,7 +245,7 @@ void MemoryPool<T>::allocateMemory() {
|
|||
MemoryUnit* currentUnit = (MemoryUnit*)( (char*)mPBlocks + i *
|
||||
(sizeof(T) + sizeof(MemoryUnit)) );
|
||||
|
||||
currentUnit->pPrevious = 0;
|
||||
currentUnit->pPrevious = NULL;
|
||||
currentUnit->pNext = mPFreeUnits;
|
||||
|
||||
if (mPFreeUnits) {
|
||||
|
|
Loading…
Reference in New Issue
Block a user