Start replacing NULL constant by nullptr

This commit is contained in:
Daniel Chappuis 2016-05-15 19:25:58 +02:00
parent 3109b4e8da
commit 2640fbd48a
32 changed files with 145 additions and 147 deletions

View File

@ -36,7 +36,7 @@ using namespace reactphysics3d;
*/
Body::Body(bodyindex id)
: mID(id), mIsAlreadyInIsland(false), mIsAllowedToSleep(true), mIsActive(true),
mIsSleeping(false), mSleepTime(0), mUserData(NULL) {
mIsSleeping(false), mSleepTime(0), mUserData(nullptr) {
}

View File

@ -38,14 +38,14 @@ using namespace reactphysics3d;
* @param id ID of the body
*/
CollisionBody::CollisionBody(const Transform& transform, CollisionWorld& world, bodyindex id)
: Body(id), mType(DYNAMIC), mTransform(transform), mProxyCollisionShapes(NULL),
mNbCollisionShapes(0), mContactManifoldsList(NULL), mWorld(world) {
: Body(id), mType(DYNAMIC), mTransform(transform), mProxyCollisionShapes(nullptr),
mNbCollisionShapes(0), mContactManifoldsList(nullptr), mWorld(world) {
}
// Destructor
CollisionBody::~CollisionBody() {
assert(mContactManifoldsList == NULL);
assert(mContactManifoldsList == nullptr);
// Remove all the proxy collision shapes of the body
removeAllCollisionShapes();
@ -75,7 +75,7 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape,
transform, decimal(1));
// Add it to the list of proxy collision shapes of the body
if (mProxyCollisionShapes == NULL) {
if (mProxyCollisionShapes == nullptr) {
mProxyCollisionShapes = proxyShape;
}
else {
@ -122,7 +122,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) {
}
// Look for the proxy shape that contains the collision shape in parameter
while(current->mNext != NULL) {
while(current->mNext != nullptr) {
// If we have found the collision shape to remove
if (current->mNext == proxyShape) {
@ -152,7 +152,7 @@ void CollisionBody::removeAllCollisionShapes() {
ProxyShape* current = mProxyCollisionShapes;
// Look for the proxy shape that contains the collision shape in parameter
while(current != NULL) {
while(current != nullptr) {
// Remove the proxy collision shape
ProxyShape* nextElement = current->mNext;
@ -168,7 +168,7 @@ void CollisionBody::removeAllCollisionShapes() {
current = nextElement;
}
mProxyCollisionShapes = NULL;
mProxyCollisionShapes = nullptr;
}
// Reset the contact manifold lists
@ -176,7 +176,7 @@ void CollisionBody::resetContactManifoldsList() {
// Delete the linked list of contact manifolds of that body
ContactManifoldListElement* currentElement = mContactManifoldsList;
while (currentElement != NULL) {
while (currentElement != nullptr) {
ContactManifoldListElement* nextElement = currentElement->next;
// Delete the current element
@ -185,14 +185,14 @@ void CollisionBody::resetContactManifoldsList() {
currentElement = nextElement;
}
mContactManifoldsList = NULL;
mContactManifoldsList = nullptr;
}
// Update the broad-phase state for this body (because it has moved for instance)
void CollisionBody::updateBroadPhaseState() const {
// For all the proxy collision shapes of the body
for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) {
for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) {
// Update the proxy
updateProxyShapeInBroadPhase(shape);
@ -225,7 +225,7 @@ void CollisionBody::setIsActive(bool isActive) {
if (isActive) {
// For each proxy shape of the body
for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) {
for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) {
// Compute the world-space AABB of the new collision shape
AABB aabb;
@ -238,7 +238,7 @@ void CollisionBody::setIsActive(bool isActive) {
else { // If we have to deactivate the body
// For each proxy shape of the body
for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) {
for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) {
// Remove the proxy shape from the collision detection
mWorld.mCollisionDetection.removeProxyCollisionShape(shape);
@ -254,7 +254,7 @@ void CollisionBody::setIsActive(bool isActive) {
void CollisionBody::askForBroadPhaseCollisionCheck() const {
// For all the proxy collision shapes of the body
for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) {
for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) {
mWorld.mCollisionDetection.askForBroadPhaseCollisionCheck(shape);
}
@ -271,7 +271,7 @@ int CollisionBody::resetIsAlreadyInIslandAndCountManifolds() {
// Reset the mIsAlreadyInIsland variable of the contact manifolds for
// this body
ContactManifoldListElement* currentElement = mContactManifoldsList;
while (currentElement != NULL) {
while (currentElement != nullptr) {
currentElement->contactManifold->mIsAlreadyInIsland = false;
currentElement = currentElement->next;
nbManifolds++;
@ -289,7 +289,7 @@ int CollisionBody::resetIsAlreadyInIslandAndCountManifolds() {
bool CollisionBody::testPointInside(const Vector3& worldPoint) const {
// For each collision shape of the body
for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) {
for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) {
// Test if the point is inside the collision shape
if (shape->testPointInside(worldPoint)) return true;
@ -315,7 +315,7 @@ bool CollisionBody::raycast(const Ray& ray, RaycastInfo& raycastInfo) {
Ray rayTemp(ray);
// For each collision shape of the body
for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) {
for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) {
// Test if the ray hits the collision shape
if (shape->raycast(rayTemp, raycastInfo)) {
@ -335,12 +335,12 @@ AABB CollisionBody::getAABB() const {
AABB bodyAABB;
if (mProxyCollisionShapes == NULL) return bodyAABB;
if (mProxyCollisionShapes == nullptr) return bodyAABB;
mProxyCollisionShapes->getCollisionShape()->computeAABB(bodyAABB, mTransform * mProxyCollisionShapes->getLocalToBodyTransform());
// For each proxy shape of the body
for (ProxyShape* shape = mProxyCollisionShapes->mNext; shape != NULL; shape = shape->mNext) {
for (ProxyShape* shape = mProxyCollisionShapes->mNext; shape != nullptr; shape = shape->mNext) {
// Compute the world-space AABB of the collision shape
AABB aabb;

View File

@ -42,7 +42,7 @@ RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyinde
: CollisionBody(transform, world, id), mInitMass(decimal(1.0)),
mCenterOfMassLocal(0, 0, 0), mCenterOfMassWorld(transform.getPosition()),
mIsGravityEnabled(true), mLinearDamping(decimal(0.0)), mAngularDamping(decimal(0.0)),
mJointsList(NULL) {
mJointsList(nullptr) {
// Compute the inverse mass
mMassInverse = decimal(1.0) / mInitMass;
@ -50,7 +50,7 @@ RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyinde
// Destructor
RigidBody::~RigidBody() {
assert(mJointsList == NULL);
assert(mJointsList == nullptr);
}
// Set the type of the body
@ -168,8 +168,8 @@ void RigidBody::setMass(decimal mass) {
// Remove a joint from the joints list
void RigidBody::removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Joint* joint) {
assert(joint != NULL);
assert(mJointsList != NULL);
assert(joint != nullptr);
assert(mJointsList != nullptr);
// Remove the joint from the linked list of the joints of the first body
if (mJointsList->joint == joint) { // If the first element is the one to remove
@ -180,7 +180,7 @@ void RigidBody::removeJointFromJointsList(MemoryAllocator& memoryAllocator, cons
}
else { // If the element to remove is not the first one in the list
JointListElement* currentElement = mJointsList;
while (currentElement->next != NULL) {
while (currentElement->next != nullptr) {
if (currentElement->next->joint == joint) {
JointListElement* elementToRemove = currentElement->next;
currentElement->next = elementToRemove->next;
@ -213,15 +213,13 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape,
const Transform& transform,
decimal mass) {
assert(mass > decimal(0.0));
// Create a new proxy collision shape to attach the collision shape to the body
ProxyShape* proxyShape = new (mWorld.mMemoryAllocator.allocate(
sizeof(ProxyShape))) ProxyShape(this, collisionShape,
transform, mass);
// Add it to the list of proxy collision shapes of the body
if (mProxyCollisionShapes == NULL) {
if (mProxyCollisionShapes == nullptr) {
mProxyCollisionShapes = proxyShape;
}
else {
@ -339,7 +337,7 @@ void RigidBody::recomputeMassInformation() {
assert(mType == DYNAMIC);
// Compute the total mass of the body
for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) {
for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) {
mInitMass += shape->getMass();
mCenterOfMassLocal += shape->getLocalToBodyTransform().getPosition() * shape->getMass();
}
@ -358,7 +356,7 @@ void RigidBody::recomputeMassInformation() {
mCenterOfMassWorld = mTransform * mCenterOfMassLocal;
// Compute the total mass and inertia tensor using all the collision shapes
for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) {
for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) {
// Get the inertia tensor of the collision shape in its local-space
Matrix3x3 inertiaTensor;
@ -401,7 +399,7 @@ void RigidBody::updateBroadPhaseState() const {
const Vector3 displacement = world.mTimeStep * mLinearVelocity;
// For all the proxy collision shapes of the body
for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) {
for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) {
// Recompute the world-space AABB of the collision shape
AABB aabb;

View File

@ -140,7 +140,7 @@ void CollisionDetection::reportCollisionBetweenShapes(CollisionCallback* callbac
contactPoint->getLocalPointOnBody2());
// Notify the collision callback about this new contact
if (callback != NULL) callback->notifyContact(contactInfo);
if (callback != nullptr) callback->notifyContact(contactInfo);
}
}
}
@ -223,7 +223,7 @@ void CollisionDetection::computeNarrowPhase() {
NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Type][shape2Type];
// If there is no collision algorithm between those two kinds of shapes
if (narrowPhaseAlgorithm == NULL) continue;
if (narrowPhaseAlgorithm == nullptr) continue;
// Notify the narrow-phase algorithm about the overlapping pair we are going to test
narrowPhaseAlgorithm->setCurrentOverlappingPair(pair);
@ -325,7 +325,7 @@ void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* call
NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Type][shape2Type];
// If there is no collision algorithm between those two kinds of shapes
if (narrowPhaseAlgorithm == NULL) continue;
if (narrowPhaseAlgorithm == nullptr) continue;
// Notify the narrow-phase algorithm about the overlapping pair we are going to test
narrowPhaseAlgorithm->setCurrentOverlappingPair(pair);
@ -373,7 +373,7 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro
// Create the overlapping pair and add it into the set of overlapping pairs
OverlappingPair* newPair = new (mWorld->mMemoryAllocator.allocate(sizeof(OverlappingPair)))
OverlappingPair(shape1, shape2, nbMaxManifolds, mWorld->mMemoryAllocator);
assert(newPair != NULL);
assert(newPair != nullptr);
#ifndef NDEBUG
std::pair<map<overlappingpairid, OverlappingPair*>::iterator, bool> check =
@ -420,14 +420,14 @@ void CollisionDetection::notifyContact(OverlappingPair* overlappingPair, const C
if (overlappingPair->getNbContactPoints() == 0) {
// Trigger a callback event
if (mWorld->mEventListener != NULL) mWorld->mEventListener->beginContact(contactInfo);
if (mWorld->mEventListener != nullptr) mWorld->mEventListener->beginContact(contactInfo);
}
// Create a new contact
createContact(overlappingPair, contactInfo);
// Trigger a callback event for the new contact
if (mWorld->mEventListener != NULL) mWorld->mEventListener->newContact(contactInfo);
if (mWorld->mEventListener != nullptr) mWorld->mEventListener->newContact(contactInfo);
}
// Create a new contact
@ -463,7 +463,7 @@ void CollisionDetection::addAllContactManifoldsToBodies() {
// in the corresponding contact
void CollisionDetection::addContactManifoldToBody(OverlappingPair* pair) {
assert(pair != NULL);
assert(pair != nullptr);
CollisionBody* body1 = pair->getShape1()->getBody();
CollisionBody* body2 = pair->getShape2()->getBody();

View File

@ -37,7 +37,7 @@ using namespace reactphysics3d;
*/
ProxyShape::ProxyShape(CollisionBody* body, CollisionShape* shape, const Transform& transform, decimal mass)
:mBody(body), mCollisionShape(shape), mLocalToBodyTransform(transform), mMass(mass),
mNext(NULL), mBroadPhaseID(-1), mCachedCollisionData(NULL), mUserData(NULL),
mNext(nullptr), mBroadPhaseID(-1), mCachedCollisionData(nullptr), mUserData(nullptr),
mCollisionCategoryBits(0x0001), mCollideWithMaskBits(0xFFFF) {
}
@ -46,7 +46,7 @@ ProxyShape::ProxyShape(CollisionBody* body, CollisionShape* shape, const Transfo
ProxyShape::~ProxyShape() {
// Release the cached collision data memory
if (mCachedCollisionData != NULL) {
if (mCachedCollisionData != nullptr) {
free(mCachedCollisionData);
}
}

View File

@ -83,7 +83,7 @@ struct RaycastInfo {
// -------------------- Methods -------------------- //
/// Constructor
RaycastInfo() : meshSubpart(-1), triangleIndex(-1), body(NULL), proxyShape(NULL) {
RaycastInfo() : meshSubpart(-1), triangleIndex(-1), body(nullptr), proxyShape(nullptr) {
}

View File

@ -39,11 +39,11 @@ BroadPhaseAlgorithm::BroadPhaseAlgorithm(CollisionDetection& collisionDetection)
// Allocate memory for the array of non-static proxy shapes IDs
mMovedShapes = (int*) malloc(mNbAllocatedMovedShapes * sizeof(int));
assert(mMovedShapes != NULL);
assert(mMovedShapes != nullptr);
// Allocate memory for the array of potential overlapping pairs
mPotentialPairs = (BroadPhasePair*) malloc(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair));
assert(mPotentialPairs != NULL);
assert(mPotentialPairs != nullptr);
}
// Destructor
@ -65,14 +65,14 @@ void BroadPhaseAlgorithm::addMovedCollisionShape(int broadPhaseID) {
mNbAllocatedMovedShapes *= 2;
int* oldArray = mMovedShapes;
mMovedShapes = (int*) malloc(mNbAllocatedMovedShapes * sizeof(int));
assert(mMovedShapes != NULL);
assert(mMovedShapes != nullptr);
memcpy(mMovedShapes, oldArray, mNbMovedShapes * sizeof(int));
free(oldArray);
}
// Store the broad-phase ID into the array of shapes that have moved
assert(mNbMovedShapes < mNbAllocatedMovedShapes);
assert(mMovedShapes != NULL);
assert(mMovedShapes != nullptr);
mMovedShapes[mNbMovedShapes] = broadPhaseID;
mNbMovedShapes++;
}
@ -91,7 +91,7 @@ void BroadPhaseAlgorithm::removeMovedCollisionShape(int broadPhaseID) {
mNbAllocatedMovedShapes /= 2;
int* oldArray = mMovedShapes;
mMovedShapes = (int*) malloc(mNbAllocatedMovedShapes * sizeof(int));
assert(mMovedShapes != NULL);
assert(mMovedShapes != nullptr);
uint nbElements = 0;
for (uint i=0; i<mNbMovedShapes; i++) {
if (oldArray[i] != -1) {

View File

@ -115,7 +115,7 @@ void ConvexVsTriangleCallback::testTriangle(const Vector3* trianglePoints) {
mConvexShape->getType());
// If there is no collision algorithm between those two kinds of shapes
if (algo == NULL) return;
if (algo == nullptr) return;
// Notify the narrow-phase algorithm about the overlapping pair we are going to test
algo->setCurrentOverlappingPair(mOverlappingPair);

View File

@ -70,6 +70,6 @@ NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int t
return &mGJKAlgorithm;
}
else {
return NULL;
return nullptr;
}
}

View File

@ -231,7 +231,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple
TriangleEPA* face3 = triangleStore.newTriangle(points, 1, 3, 2);
// If the constructed tetrahedron is not correct
if (!((face0 != NULL) && (face1 != NULL) && (face2 != NULL) && (face3 != NULL)
if (!((face0 != nullptr) && (face1 != nullptr) && (face2 != nullptr) && (face3 != nullptr)
&& face0->getDistSquare() > 0.0 && face1->getDistSquare() > 0.0
&& face2->getDistSquare() > 0.0 && face3->getDistSquare() > 0.0)) {
return;
@ -289,10 +289,10 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple
shape2->getLocalSupportPointWithMargin(rotateToBody2 * n, shape2CachedCollisionData);
points[4] = suppPointsA[4] - suppPointsB[4];
TriangleEPA* face0 = NULL;
TriangleEPA* face1 = NULL;
TriangleEPA* face2 = NULL;
TriangleEPA* face3 = NULL;
TriangleEPA* face0 = nullptr;
TriangleEPA* face1 = nullptr;
TriangleEPA* face2 = nullptr;
TriangleEPA* face3 = nullptr;
// If the origin is in the first tetrahedron
if (isOriginInTetrahedron(points[0], points[1],
@ -323,7 +323,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple
}
// If the constructed tetrahedron is not correct
if (!((face0 != NULL) && (face1 != NULL) && (face2 != NULL) && (face3 != NULL)
if (!((face0 != nullptr) && (face1 != nullptr) && (face2 != nullptr) && (face3 != nullptr)
&& face0->getDistSquare() > 0.0 && face1->getDistSquare() > 0.0
&& face2->getDistSquare() > 0.0 && face3->getDistSquare() > 0.0)) {
return;

View File

@ -78,7 +78,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex,
getSourceVertexIndex());
// If the triangle has been created
if (triangle != NULL) {
if (triangle != nullptr) {
halfLink(EdgeEPA(triangle, 1), *this);
return true;
}
@ -103,7 +103,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex,
getSourceVertexIndex());
// If the triangle has been created
if (triangle != NULL) {
if (triangle != nullptr) {
halfLink(EdgeEPA(triangle, 1), *this);
return true;
}
@ -122,7 +122,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex,
getTargetVertexIndex(),
getSourceVertexIndex());
if (triangle != NULL) {
if (triangle != nullptr) {
halfLink(EdgeEPA(triangle, 1), *this);
return true;
}

View File

@ -115,7 +115,7 @@ inline TriangleEPA& TrianglesStore::last() {
// Create a new triangle
inline TriangleEPA* TrianglesStore::newTriangle(const Vector3* vertices,
uint v0,uint v1, uint v2) {
TriangleEPA* newTriangle = NULL;
TriangleEPA* newTriangle = nullptr;
// If we have not reached the maximum number of triangles
if (mNbTriangles != MAX_TRIANGLES) {
@ -123,7 +123,7 @@ inline TriangleEPA* TrianglesStore::newTriangle(const Vector3* vertices,
new (newTriangle) TriangleEPA(v0, v1, v2);
if (!newTriangle->computeClosestPoint(vertices)) {
mNbTriangles--;
newTriangle = NULL;
newTriangle = nullptr;
}
}

View File

@ -31,7 +31,7 @@ using namespace reactphysics3d;
// Constructor
NarrowPhaseAlgorithm::NarrowPhaseAlgorithm()
: mMemoryAllocator(NULL), mCurrentOverlappingPair(NULL) {
: mMemoryAllocator(nullptr), mCurrentOverlappingPair(nullptr) {
}

View File

@ -137,7 +137,7 @@ bool ConeShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* pr
}
// If the origin of the ray is inside the cone, we return no hit
if (testPointInside(ray.point1, NULL)) return false;
if (testPointInside(ray.point1, nullptr)) return false;
localHitPoint[0] = ray.point1 + tHit[0] * r;
localHitPoint[1] = ray.point1 + tHit[1] * r;

View File

@ -157,10 +157,10 @@ Vector3 ConvexMeshShape::getLocalSupportPointWithoutMargin(const Vector3& direct
void** cachedCollisionData) const {
assert(mNbVertices == mVertices.size());
assert(cachedCollisionData != NULL);
assert(cachedCollisionData != nullptr);
// Allocate memory for the cached collision data if not allocated yet
if ((*cachedCollisionData) == NULL) {
if ((*cachedCollisionData) == nullptr) {
*cachedCollisionData = (int*) malloc(sizeof(int));
*((int*)(*cachedCollisionData)) = 0;
}

View File

@ -34,8 +34,8 @@ Joint::Joint(const JointInfo& jointInfo)
mPositionCorrectionTechnique(jointInfo.positionCorrectionTechnique),
mIsCollisionEnabled(jointInfo.isCollisionEnabled), mIsAlreadyInIsland(false) {
assert(mBody1 != NULL);
assert(mBody2 != NULL);
assert(mBody1 != nullptr);
assert(mBody2 != nullptr);
}
// Destructor

View File

@ -94,7 +94,7 @@ struct JointInfo {
/// Constructor
JointInfo(JointType constraintType)
: body1(NULL), body2(NULL), type(constraintType),
: body1(nullptr), body2(nullptr), type(constraintType),
positionCorrectionTechnique(NON_LINEAR_GAUSS_SEIDEL),
isCollisionEnabled(true) {}

View File

@ -34,7 +34,7 @@ using namespace std;
// Constructor
CollisionWorld::CollisionWorld()
: mCollisionDetection(this, mMemoryAllocator), mCurrentBodyID(0),
mEventListener(NULL) {
mEventListener(nullptr) {
}
@ -69,7 +69,7 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) {
CollisionBody* collisionBody = new (mMemoryAllocator.allocate(sizeof(CollisionBody)))
CollisionBody(transform, *this, bodyID);
assert(collisionBody != NULL);
assert(collisionBody != nullptr);
// Add the collision body to the world
mBodies.insert(collisionBody);
@ -208,7 +208,7 @@ void CollisionWorld::testCollision(const CollisionBody* body,
std::set<uint> shapes1;
// For each shape of the body
for (const ProxyShape* shape=body->getProxyShapesList(); shape != NULL;
for (const ProxyShape* shape=body->getProxyShapesList(); shape != nullptr;
shape = shape->getNext()) {
shapes1.insert(shape->mBroadPhaseID);
}
@ -234,13 +234,13 @@ void CollisionWorld::testCollision(const CollisionBody* body1,
// Create the sets of shapes
std::set<uint> shapes1;
for (const ProxyShape* shape=body1->getProxyShapesList(); shape != NULL;
for (const ProxyShape* shape=body1->getProxyShapesList(); shape != nullptr;
shape = shape->getNext()) {
shapes1.insert(shape->mBroadPhaseID);
}
std::set<uint> shapes2;
for (const ProxyShape* shape=body2->getProxyShapesList(); shape != NULL;
for (const ProxyShape* shape=body2->getProxyShapesList(); shape != nullptr;
shape = shape->getNext()) {
shapes2.insert(shape->mBroadPhaseID);
}

View File

@ -46,7 +46,7 @@ void ConstraintSolver::initializeForIsland(decimal dt, Island* island) {
PROFILE("ConstraintSolver::initializeForIsland()");
assert(island != NULL);
assert(island != nullptr);
assert(island->getNbBodies() > 0);
assert(island->getNbJoints() > 0);
@ -76,7 +76,7 @@ void ConstraintSolver::solveVelocityConstraints(Island* island) {
PROFILE("ConstraintSolver::solveVelocityConstraints()");
assert(island != NULL);
assert(island != nullptr);
assert(island->getNbJoints() > 0);
// For each joint of the island
@ -93,7 +93,7 @@ void ConstraintSolver::solvePositionConstraints(Island* island) {
PROFILE("ConstraintSolver::solvePositionConstraints()");
assert(island != NULL);
assert(island != nullptr);
assert(island->getNbJoints() > 0);
// For each joint of the island

View File

@ -69,8 +69,8 @@ struct ConstraintSolverData {
/// Constructor
ConstraintSolverData(const std::map<RigidBody*, uint>& refMapBodyToConstrainedVelocityIndex)
:linearVelocities(NULL), angularVelocities(NULL),
positions(NULL), orientations(NULL),
:linearVelocities(nullptr), angularVelocities(nullptr),
positions(nullptr), orientations(nullptr),
mapBodyToConstrainedVelocityIndex(refMapBodyToConstrainedVelocityIndex){
}
@ -202,8 +202,8 @@ class ConstraintSolver {
// Set the constrained velocities arrays
inline void ConstraintSolver::setConstrainedVelocitiesArrays(Vector3* constrainedLinearVelocities,
Vector3* constrainedAngularVelocities) {
assert(constrainedLinearVelocities != NULL);
assert(constrainedAngularVelocities != NULL);
assert(constrainedLinearVelocities != nullptr);
assert(constrainedAngularVelocities != nullptr);
mConstraintSolverData.linearVelocities = constrainedLinearVelocities;
mConstraintSolverData.angularVelocities = constrainedAngularVelocities;
}
@ -211,8 +211,8 @@ inline void ConstraintSolver::setConstrainedVelocitiesArrays(Vector3* constraine
// Set the constrained positions/orientations arrays
inline void ConstraintSolver::setConstrainedPositionsArrays(Vector3* constrainedPositions,
Quaternion* constrainedOrientations) {
assert(constrainedPositions != NULL);
assert(constrainedOrientations != NULL);
assert(constrainedPositions != nullptr);
assert(constrainedOrientations != nullptr);
mConstraintSolverData.positions = constrainedPositions;
mConstraintSolverData.orientations = constrainedOrientations;
}

View File

@ -40,8 +40,8 @@ const decimal ContactSolver::SLOP= decimal(0.01);
// Constructor
ContactSolver::ContactSolver(const std::map<RigidBody*, uint>& mapBodyToVelocityIndex)
:mSplitLinearVelocities(NULL), mSplitAngularVelocities(NULL),
mContactConstraints(NULL), mLinearVelocities(NULL), mAngularVelocities(NULL),
:mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr),
mContactConstraints(nullptr), mLinearVelocities(nullptr), mAngularVelocities(nullptr),
mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex),
mIsWarmStartingActive(true), mIsSplitImpulseActive(true),
mIsSolveFrictionAtContactManifoldCenterActive(true) {
@ -58,11 +58,11 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) {
PROFILE("ContactSolver::initializeForIsland()");
assert(island != NULL);
assert(island != nullptr);
assert(island->getNbBodies() > 0);
assert(island->getNbContactManifolds() > 0);
assert(mSplitLinearVelocities != NULL);
assert(mSplitAngularVelocities != NULL);
assert(mSplitLinearVelocities != nullptr);
assert(mSplitAngularVelocities != nullptr);
// Set the current time step
mTimeStep = dt;
@ -70,7 +70,7 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) {
mNbContactManifolds = island->getNbContactManifolds();
mContactConstraints = new ContactManifoldSolver[mNbContactManifolds];
assert(mContactConstraints != NULL);
assert(mContactConstraints != nullptr);
// For each contact manifold of the island
ContactManifold** contactManifolds = island->getContactManifold();
@ -85,8 +85,8 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) {
// Get the two bodies of the contact
RigidBody* body1 = static_cast<RigidBody*>(externalManifold->getContactPoint(0)->getBody1());
RigidBody* body2 = static_cast<RigidBody*>(externalManifold->getContactPoint(0)->getBody2());
assert(body1 != NULL);
assert(body2 != NULL);
assert(body1 != nullptr);
assert(body2 != nullptr);
// Get the position of the two bodies
const Vector3& x1 = body1->mCenterOfMassWorld;

View File

@ -453,8 +453,8 @@ class ContactSolver {
// Set the split velocities arrays
inline void ContactSolver::setSplitVelocitiesArrays(Vector3* splitLinearVelocities,
Vector3* splitAngularVelocities) {
assert(splitLinearVelocities != NULL);
assert(splitAngularVelocities != NULL);
assert(splitLinearVelocities != nullptr);
assert(splitAngularVelocities != nullptr);
mSplitLinearVelocities = splitLinearVelocities;
mSplitAngularVelocities = splitAngularVelocities;
}
@ -462,8 +462,8 @@ inline void ContactSolver::setSplitVelocitiesArrays(Vector3* splitLinearVelociti
// Set the constrained velocities arrays
inline void ContactSolver::setConstrainedVelocitiesArrays(Vector3* constrainedLinearVelocities,
Vector3* constrainedAngularVelocities) {
assert(constrainedLinearVelocities != NULL);
assert(constrainedAngularVelocities != NULL);
assert(constrainedLinearVelocities != nullptr);
assert(constrainedAngularVelocities != nullptr);
mLinearVelocities = constrainedLinearVelocities;
mAngularVelocities = constrainedAngularVelocities;
}

View File

@ -45,11 +45,11 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity)
mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS),
mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS),
mIsSleepingEnabled(SPLEEPING_ENABLED), mGravity(gravity),
mIsGravityEnabled(true), mConstrainedLinearVelocities(NULL),
mConstrainedAngularVelocities(NULL), mSplitLinearVelocities(NULL),
mSplitAngularVelocities(NULL), mConstrainedPositions(NULL),
mConstrainedOrientations(NULL), mNbIslands(0),
mNbIslandsCapacity(0), mIslands(NULL), mNbBodiesCapacity(0),
mIsGravityEnabled(true), mConstrainedLinearVelocities(nullptr),
mConstrainedAngularVelocities(nullptr), mSplitLinearVelocities(nullptr),
mSplitAngularVelocities(nullptr), mConstrainedPositions(nullptr),
mConstrainedOrientations(nullptr), mNbIslands(0),
mNbIslandsCapacity(0), mIslands(nullptr), mNbBodiesCapacity(0),
mSleepLinearVelocity(DEFAULT_SLEEP_LINEAR_VELOCITY),
mSleepAngularVelocity(DEFAULT_SLEEP_ANGULAR_VELOCITY),
mTimeBeforeSleep(DEFAULT_TIME_BEFORE_SLEEP) {
@ -128,7 +128,7 @@ void DynamicsWorld::update(decimal timeStep) {
mTimeStep = timeStep;
// Notify the event listener about the beginning of an internal tick
if (mEventListener != NULL) mEventListener->beginInternalTick();
if (mEventListener != nullptr) mEventListener->beginInternalTick();
// Reset all the contact manifolds lists of each body
resetContactManifoldListsOfBodies();
@ -157,7 +157,7 @@ void DynamicsWorld::update(decimal timeStep) {
if (mIsSleepingEnabled) updateSleepingBodies();
// Notify the event listener about the end of an internal tick
if (mEventListener != NULL) mEventListener->endInternalTick();
if (mEventListener != nullptr) mEventListener->endInternalTick();
// Reset the external force and torque applied to the bodies
resetBodiesForceAndTorque();
@ -256,12 +256,12 @@ void DynamicsWorld::initVelocityArrays() {
mConstrainedAngularVelocities = new Vector3[mNbBodiesCapacity];
mConstrainedPositions = new Vector3[mNbBodiesCapacity];
mConstrainedOrientations = new Quaternion[mNbBodiesCapacity];
assert(mSplitLinearVelocities != NULL);
assert(mSplitAngularVelocities != NULL);
assert(mConstrainedLinearVelocities != NULL);
assert(mConstrainedAngularVelocities != NULL);
assert(mConstrainedPositions != NULL);
assert(mConstrainedOrientations != NULL);
assert(mSplitLinearVelocities != nullptr);
assert(mSplitAngularVelocities != nullptr);
assert(mConstrainedLinearVelocities != nullptr);
assert(mConstrainedAngularVelocities != nullptr);
assert(mConstrainedPositions != nullptr);
assert(mConstrainedOrientations != nullptr);
}
// Reset the velocities arrays
@ -448,7 +448,7 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) {
// Create the rigid body
RigidBody* rigidBody = new (mMemoryAllocator.allocate(sizeof(RigidBody))) RigidBody(transform,
*this, bodyID);
assert(rigidBody != NULL);
assert(rigidBody != nullptr);
// Add the rigid body to the physics world
mBodies.insert(rigidBody);
@ -472,7 +472,7 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) {
// Destroy all the joints in which the rigid body to be destroyed is involved
JointListElement* element;
for (element = rigidBody->mJointsList; element != NULL; element = element->next) {
for (element = rigidBody->mJointsList; element != nullptr; element = element->next) {
destroyJoint(element->joint);
}
@ -497,7 +497,7 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) {
*/
Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) {
Joint* newJoint = NULL;
Joint* newJoint = nullptr;
// Allocate memory to create the new joint
switch(jointInfo.type) {
@ -542,7 +542,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) {
default:
{
assert(false);
return NULL;
return nullptr;
}
}
@ -569,7 +569,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) {
*/
void DynamicsWorld::destroyJoint(Joint* joint) {
assert(joint != NULL);
assert(joint != nullptr);
// If the collision between the two bodies of the constraint was disabled
if (!joint->isCollisionEnabled()) {
@ -601,7 +601,7 @@ void DynamicsWorld::destroyJoint(Joint* joint) {
// Add the joint to the list of joints of the two bodies involved in the joint
void DynamicsWorld::addJointToBody(Joint* joint) {
assert(joint != NULL);
assert(joint != nullptr);
// Add the joint at the beginning of the linked list of joints of the first body
void* allocatedMemory1 = mMemoryAllocator.allocate(sizeof(JointListElement));
@ -710,7 +710,7 @@ void DynamicsWorld::computeIslands() {
// For each contact manifold in which the current body is involded
ContactManifoldListElement* contactElement;
for (contactElement = bodyToVisit->mContactManifoldsList; contactElement != NULL;
for (contactElement = bodyToVisit->mContactManifoldsList; contactElement != nullptr;
contactElement = contactElement->next) {
ContactManifold* contactManifold = contactElement->contactManifold;
@ -740,7 +740,7 @@ void DynamicsWorld::computeIslands() {
// For each joint in which the current body is involved
JointListElement* jointElement;
for (jointElement = bodyToVisit->mJointsList; jointElement != NULL;
for (jointElement = bodyToVisit->mJointsList; jointElement != nullptr;
jointElement = jointElement->next) {
Joint* joint = jointElement->joint;
@ -916,7 +916,7 @@ void DynamicsWorld::testCollision(const CollisionBody* body,
std::set<uint> shapes1;
// For each shape of the body
for (const ProxyShape* shape=body->getProxyShapesList(); shape != NULL;
for (const ProxyShape* shape=body->getProxyShapesList(); shape != nullptr;
shape = shape->getNext()) {
shapes1.insert(shape->mBroadPhaseID);
}
@ -941,13 +941,13 @@ void DynamicsWorld::testCollision(const CollisionBody* body1,
// Create the sets of shapes
std::set<uint> shapes1;
for (const ProxyShape* shape=body1->getProxyShapesList(); shape != NULL;
for (const ProxyShape* shape=body1->getProxyShapesList(); shape != nullptr;
shape = shape->getNext()) {
shapes1.insert(shape->mBroadPhaseID);
}
std::set<uint> shapes2;
for (const ProxyShape* shape=body2->getProxyShapesList(); shape != NULL;
for (const ProxyShape* shape=body2->getProxyShapesList(); shape != nullptr;
shape = shape->getNext()) {
shapes2.insert(shape->mBroadPhaseID);
}

View File

@ -512,7 +512,7 @@ inline void DynamicsWorld::setTimeBeforeSleep(decimal timeBeforeSleep) {
}
// Set an event listener object to receive events callbacks.
/// If you use NULL as an argument, the events callbacks will be disabled.
/// If you use "nullptr" as an argument, the events callbacks will be disabled.
/**
* @param eventListener Pointer to the event listener object that will receive
* event callbacks during the simulation

View File

@ -31,7 +31,7 @@ using namespace reactphysics3d;
// Constructor
Island::Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints,
MemoryAllocator& memoryAllocator)
: mBodies(NULL), mContactManifolds(NULL), mJoints(NULL), mNbBodies(0),
: mBodies(nullptr), mContactManifolds(nullptr), mJoints(nullptr), mNbBodies(0),
mNbContactManifolds(0), mNbJoints(0), mMemoryAllocator(memoryAllocator) {
// Allocate memory for the arrays

View File

@ -31,7 +31,7 @@
using namespace reactphysics3d;
// Initialization of static variables
ProfileNode Profiler::mRootNode("Root", NULL);
ProfileNode Profiler::mRootNode("Root", nullptr);
ProfileNode* Profiler::mCurrentNode = &Profiler::mRootNode;
long double Profiler::mProfilingStartTime = Timer::getCurrentSystemTime() * 1000.0;
uint Profiler::mFrameCounter = 0;
@ -39,8 +39,8 @@ uint Profiler::mFrameCounter = 0;
// Constructor
ProfileNode::ProfileNode(const char* name, ProfileNode* parentNode)
:mName(name), mNbTotalCalls(0), mStartingTime(0), mTotalTime(0),
mRecursionCounter(0), mParentNode(parentNode), mChildNode(NULL),
mSiblingNode(NULL) {
mRecursionCounter(0), mParentNode(parentNode), mChildNode(nullptr),
mSiblingNode(nullptr) {
reset();
}
@ -56,7 +56,7 @@ ProfileNode* ProfileNode::findSubNode(const char* name) {
// Try to find the node among the child nodes
ProfileNode* child = mChildNode;
while (child != NULL) {
while (child != nullptr) {
if (child->mName == name) {
return child;
}
@ -110,12 +110,12 @@ void ProfileNode::reset() {
mTotalTime = 0.0;
// Reset the child node
if (mChildNode != NULL) {
if (mChildNode != nullptr) {
mChildNode->reset();
}
// Reset the sibling node
if (mSiblingNode != NULL) {
if (mSiblingNode != nullptr) {
mSiblingNode->reset();
}
}
@ -123,9 +123,9 @@ void ProfileNode::reset() {
// Destroy the node
void ProfileNode::destroy() {
delete mChildNode;
mChildNode = NULL;
mChildNode = nullptr;
delete mSiblingNode;
mSiblingNode = NULL;
mSiblingNode = nullptr;
}
// Constructor
@ -138,12 +138,12 @@ ProfileNodeIterator::ProfileNodeIterator(ProfileNode* startingNode)
// Enter a given child node
void ProfileNodeIterator::enterChild(int index) {
mCurrentChildNode = mCurrentParentNode->getChildNode();
while ((mCurrentChildNode != NULL) && (index != 0)) {
while ((mCurrentChildNode != nullptr) && (index != 0)) {
index--;
mCurrentChildNode = mCurrentChildNode->getSiblingNode();
}
if (mCurrentChildNode != NULL) {
if (mCurrentChildNode != nullptr) {
mCurrentParentNode = mCurrentChildNode;
mCurrentChildNode = mCurrentParentNode->getChildNode();
}
@ -151,7 +151,7 @@ void ProfileNodeIterator::enterChild(int index) {
// Enter a given parent node
void ProfileNodeIterator::enterParent() {
if (mCurrentParentNode->getParentNode() != NULL) {
if (mCurrentParentNode->getParentNode() != nullptr) {
mCurrentParentNode = mCurrentParentNode->getParentNode();
}
mCurrentChildNode = mCurrentParentNode->getChildNode();

View File

@ -269,12 +269,12 @@ class ProfileSample {
// Return true if we are at the root of the profiler tree
inline bool ProfileNodeIterator::isRoot() {
return (mCurrentParentNode->getParentNode() == NULL);
return (mCurrentParentNode->getParentNode() == nullptr);
}
// Return true if we are at the end of a branch of the profiler tree
inline bool ProfileNodeIterator::isEnd() {
return (mCurrentChildNode == NULL);
return (mCurrentChildNode == nullptr);
}
// Return the name of the current node

View File

@ -51,7 +51,7 @@ long double Timer::getCurrentSystemTime() {
#else
// Initialize the lastUpdateTime with the current time in seconds
timeval timeValue;
gettimeofday(&timeValue, NULL);
gettimeofday(&timeValue, nullptr);
return (timeValue.tv_sec + (timeValue.tv_usec / 1000000.0));
#endif
}

View File

@ -99,7 +99,7 @@ MemoryAllocator::~MemoryAllocator() {
void* MemoryAllocator::allocate(size_t size) {
// We cannot allocate zero bytes
if (size == 0) return NULL;
if (size == 0) return nullptr;
#ifndef NDEBUG
mNbTimesAllocateMethodCalled++;
@ -117,7 +117,7 @@ void* MemoryAllocator::allocate(size_t size) {
assert(indexHeap >= 0 && indexHeap < NB_HEAPS);
// If there still are free memory units in the corresponding heap
if (mFreeMemoryUnits[indexHeap] != NULL) {
if (mFreeMemoryUnits[indexHeap] != nullptr) {
// Return a pointer to the memory unit
MemoryUnit* unit = mFreeMemoryUnits[indexHeap];
@ -142,7 +142,7 @@ void* MemoryAllocator::allocate(size_t size) {
// memory units
MemoryBlock* newBlock = mMemoryBlocks + mNbCurrentMemoryBlocks;
newBlock->memoryUnits = (MemoryUnit*) malloc(BLOCK_SIZE);
assert(newBlock->memoryUnits != NULL);
assert(newBlock->memoryUnits != nullptr);
size_t unitSize = mUnitSizes[indexHeap];
uint nbUnits = BLOCK_SIZE / unitSize;
assert(nbUnits * unitSize <= BLOCK_SIZE);
@ -152,7 +152,7 @@ void* MemoryAllocator::allocate(size_t size) {
unit->nextUnit = nextUnit;
}
MemoryUnit* lastUnit = (MemoryUnit*) ((size_t)newBlock->memoryUnits + unitSize*(nbUnits-1));
lastUnit->nextUnit = NULL;
lastUnit->nextUnit = nullptr;
// Add the new allocated block into the list of free memory units in the heap
mFreeMemoryUnits[indexHeap] = newBlock->memoryUnits->nextUnit;

View File

@ -61,10 +61,10 @@ long TestSuite::getNbFailedTests() const {
// Add a unit test in the test suite
void TestSuite::addTest(Test* test) {
if (test == NULL) {
throw std::invalid_argument("Error : You cannot add a NULL test in the test suite.");
if (test == nullptr) {
throw std::invalid_argument("Error : You cannot add a nullptr test in the test suite.");
}
else if (mOutputStream != NULL && test->getOutputStream() == NULL) {
else if (mOutputStream != nullptr && test->getOutputStream() == nullptr) {
test->setOutputStream(mOutputStream);
}
@ -80,7 +80,7 @@ void TestSuite::addTestSuite(const TestSuite& testSuite) {
// Add each test of the test suite to the current one
for (size_t i =0; i < testSuite.mTests.size(); i++) {
assert(testSuite.mTests[i] != NULL);
assert(testSuite.mTests[i] != nullptr);
addTest(testSuite.mTests[i]);
}
}
@ -93,7 +93,7 @@ void TestSuite::run() {
// Run all the tests
for (size_t i=0; i < mTests.size(); i++) {
assert(mTests[i] != NULL);
assert(mTests[i] != nullptr);
mTests[i]->run();
}
}
@ -108,7 +108,7 @@ void TestSuite::reset() {
// Display the tests report and return the number of failed tests
long TestSuite::report() const {
if (mOutputStream != NULL) {
if (mOutputStream != nullptr) {
long nbFailedTests = 0;
*mOutputStream << "Test Suite \"" << mName << "\"\n";
@ -118,7 +118,7 @@ long TestSuite::report() const {
}
*mOutputStream << "=" << std::endl;
for (i=0; i < mTests.size(); i++) {
assert(mTests[i] != NULL);
assert(mTests[i] != nullptr);
nbFailedTests += mTests[i]->report();
}
for (i=0; i < 70; i++) {
@ -139,6 +139,6 @@ void TestSuite::clear() {
for (size_t i=0; i<mTests.size(); i++) {
delete mTests[i];
mTests[i] = NULL;
mTests[i] = nullptr;
}
}

View File

@ -60,7 +60,7 @@ class WorldRaycastCallback : public RaycastCallback {
WorldRaycastCallback() {
isHit = false;
shapeToTest = NULL;
shapeToTest = nullptr;
}
virtual decimal notifyRaycastHit(const RaycastInfo& info) {
@ -79,9 +79,9 @@ class WorldRaycastCallback : public RaycastCallback {
}
void reset() {
raycastInfo.body = NULL;
raycastInfo.body = nullptr;
raycastInfo.hitFraction = decimal(0.0);
raycastInfo.proxyShape = NULL;
raycastInfo.proxyShape = nullptr;
raycastInfo.worldNormal.setToZero();
raycastInfo.worldPoint.setToZero();
isHit = false;

View File

@ -27,7 +27,7 @@
#include "Box.h"
// Macros
#define MEMBER_OFFSET(s,m) ((char *)NULL + (offsetof(s,m)))
#define MEMBER_OFFSET(s,m) ((char *)nullptr + (offsetof(s,m)))
// Initialize static variables
openglframework::VertexBufferObject Box::mVBOVertices(GL_ARRAY_BUFFER);