[DEV] update etk null

This commit is contained in:
Edouard DUPIN 2018-06-19 22:13:48 +02:00
parent 59280cc06c
commit 42f5d84744
26 changed files with 140 additions and 140 deletions

View File

@ -18,6 +18,6 @@ ephysics::Body::Body(bodyindex _id):
m_isActive(true),
m_isSleeping(false),
m_sleepTime(0),
m_userData(nullptr) {
m_userData(null) {
}

View File

@ -18,15 +18,15 @@ CollisionBody::CollisionBody(const etk::Transform3D& _transform, CollisionWorld&
Body(_id),
m_type(DYNAMIC),
m_transform(_transform),
m_proxyCollisionShapes(nullptr),
m_proxyCollisionShapes(null),
m_numberCollisionShapes(0),
m_contactManifoldsList(nullptr),
m_contactManifoldsList(null),
m_world(_world) {
}
CollisionBody::~CollisionBody() {
assert(m_contactManifoldsList == nullptr);
assert(m_contactManifoldsList == null);
// Remove all the proxy collision shapes of the body
removeAllCollisionShapes();
@ -46,7 +46,7 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* _collisionShape,
// Create a proxy collision shape to attach the collision shape to the body
ProxyShape* proxyShape = ETK_NEW(ProxyShape, this, _collisionShape,_transform, float(1));
// Add it to the list of proxy collision shapes of the body
if (m_proxyCollisionShapes == nullptr) {
if (m_proxyCollisionShapes == null) {
m_proxyCollisionShapes = proxyShape;
} else {
proxyShape->m_next = m_proxyCollisionShapes;
@ -68,12 +68,12 @@ void CollisionBody::removeCollisionShape(const ProxyShape* _proxyShape) {
m_world.m_collisionDetection.removeProxyCollisionShape(current);
}
ETK_DELETE(ProxyShape, current);
current = nullptr;
current = null;
m_numberCollisionShapes--;
return;
}
// Look for the proxy shape that contains the collision shape in parameter
while(current->m_next != nullptr) {
while(current->m_next != null) {
// If we have found the collision shape to remove
if (current->m_next == _proxyShape) {
// Remove the proxy collision shape
@ -83,7 +83,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* _proxyShape) {
m_world.m_collisionDetection.removeProxyCollisionShape(elementToRemove);
}
ETK_DELETE(ProxyShape, elementToRemove);
elementToRemove = nullptr;
elementToRemove = null;
m_numberCollisionShapes--;
return;
}
@ -96,7 +96,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* _proxyShape) {
void CollisionBody::removeAllCollisionShapes() {
ProxyShape* current = m_proxyCollisionShapes;
// Look for the proxy shape that contains the collision shape in parameter
while(current != nullptr) {
while(current != null) {
// Remove the proxy collision shape
ProxyShape* nextElement = current->m_next;
if (m_isActive) {
@ -106,26 +106,26 @@ void CollisionBody::removeAllCollisionShapes() {
// Get the next element in the list
current = nextElement;
}
m_proxyCollisionShapes = nullptr;
m_proxyCollisionShapes = null;
}
void CollisionBody::resetContactManifoldsList() {
// Delete the linked list of contact manifolds of that body
ContactManifoldListElement* currentElement = m_contactManifoldsList;
while (currentElement != nullptr) {
while (currentElement != null) {
ContactManifoldListElement* nextElement = currentElement->next;
// Delete the current element
ETK_DELETE(ContactManifoldListElement, currentElement);
currentElement = nextElement;
}
m_contactManifoldsList = nullptr;
m_contactManifoldsList = null;
}
void CollisionBody::updateBroadPhaseState() const {
// For all the proxy collision shapes of the body
for (ProxyShape* shape = m_proxyCollisionShapes; shape != nullptr; shape = shape->m_next) {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != null; shape = shape->m_next) {
// Update the proxy
updateProxyShapeInBroadPhase(shape);
}
@ -147,13 +147,13 @@ void CollisionBody::setIsActive(bool _isActive) {
Body::setIsActive(_isActive);
// If we have to activate the body
if (_isActive == true) {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != nullptr; shape = shape->m_next) {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != null; shape = shape->m_next) {
AABB aabb;
shape->getCollisionShape()->computeAABB(aabb, m_transform * shape->m_localToBodyTransform);
m_world.m_collisionDetection.addProxyCollisionShape(shape, aabb);
}
} else {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != nullptr; shape = shape->m_next) {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != null; shape = shape->m_next) {
m_world.m_collisionDetection.removeProxyCollisionShape(shape);
}
resetContactManifoldsList();
@ -162,7 +162,7 @@ void CollisionBody::setIsActive(bool _isActive) {
void CollisionBody::askForBroadPhaseCollisionCheck() const {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != nullptr; shape = shape->m_next) {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != null; shape = shape->m_next) {
m_world.m_collisionDetection.askForBroadPhaseCollisionCheck(shape);
}
}
@ -173,7 +173,7 @@ int32_t CollisionBody::resetIsAlreadyInIslandAndCountManifolds() {
int32_t nbManifolds = 0;
// Reset the m_isAlreadyInIsland variable of the contact manifolds for this body
ContactManifoldListElement* currentElement = m_contactManifoldsList;
while (currentElement != nullptr) {
while (currentElement != null) {
currentElement->contactManifold->m_isAlreadyInIsland = false;
currentElement = currentElement->next;
nbManifolds++;
@ -182,7 +182,7 @@ int32_t CollisionBody::resetIsAlreadyInIslandAndCountManifolds() {
}
bool CollisionBody::testPointInside(const vec3& _worldPoint) const {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != nullptr; shape = shape->m_next) {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != null; shape = shape->m_next) {
if (shape->testPointInside(_worldPoint)) return true;
}
return false;
@ -194,7 +194,7 @@ bool CollisionBody::raycast(const Ray& _ray, RaycastInfo& _raycastInfo) {
}
bool isHit = false;
Ray rayTemp(_ray);
for (ProxyShape* shape = m_proxyCollisionShapes; shape != nullptr; shape = shape->m_next) {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != null; shape = shape->m_next) {
// Test if the ray hits the collision shape
if (shape->raycast(rayTemp, _raycastInfo)) {
rayTemp.maxFraction = _raycastInfo.hitFraction;
@ -206,11 +206,11 @@ bool CollisionBody::raycast(const Ray& _ray, RaycastInfo& _raycastInfo) {
AABB CollisionBody::getAABB() const {
AABB bodyAABB;
if (m_proxyCollisionShapes == nullptr) {
if (m_proxyCollisionShapes == null) {
return bodyAABB;
}
m_proxyCollisionShapes->getCollisionShape()->computeAABB(bodyAABB, m_transform * m_proxyCollisionShapes->getLocalToBodyTransform());
for (ProxyShape* shape = m_proxyCollisionShapes->m_next; shape != nullptr; shape = shape->m_next) {
for (ProxyShape* shape = m_proxyCollisionShapes->m_next; shape != null; shape = shape->m_next) {
AABB aabb;
shape->getCollisionShape()->computeAABB(aabb, m_transform * shape->getLocalToBodyTransform());
bodyAABB.mergeWithAABB(aabb);

View File

@ -23,13 +23,13 @@ RigidBody::RigidBody(const etk::Transform3D& _transform, CollisionWorld& _world,
m_isGravityEnabled(true),
m_linearDamping(0.0f),
m_angularDamping(float(0.0)),
m_jointsList(nullptr) {
m_jointsList(null) {
// Compute the inverse mass
m_massInverse = 1.0f / m_initMass;
}
RigidBody::~RigidBody() {
assert(m_jointsList == nullptr);
assert(m_jointsList == null);
}
@ -97,23 +97,23 @@ void RigidBody::setMass(float _mass) {
}
void RigidBody::removeJointFrom_jointsList(const Joint* _joint) {
assert(_joint != nullptr);
assert(m_jointsList != nullptr);
assert(_joint != null);
assert(m_jointsList != null);
// Remove the joint from the linked list of the joints of the first body
if (m_jointsList->joint == _joint) { // If the first element is the one to remove
JointListElement* elementToRemove = m_jointsList;
m_jointsList = elementToRemove->next;
ETK_DELETE(JointListElement, elementToRemove);
elementToRemove = nullptr;
elementToRemove = null;
}
else { // If the element to remove is not the first one in the list
JointListElement* currentElement = m_jointsList;
while (currentElement->next != nullptr) {
while (currentElement->next != null) {
if (currentElement->next->joint == _joint) {
JointListElement* elementToRemove = currentElement->next;
currentElement->next = elementToRemove->next;
ETK_DELETE(JointListElement, elementToRemove);
elementToRemove = nullptr;
elementToRemove = null;
break;
}
currentElement = currentElement->next;
@ -129,7 +129,7 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* _collisionShape,
// Create a new proxy collision shape to attach the collision shape to the body
ProxyShape* proxyShape = ETK_NEW(ProxyShape, this, _collisionShape, _transform, _mass);
// Add it to the list of proxy collision shapes of the body
if (m_proxyCollisionShapes == nullptr) {
if (m_proxyCollisionShapes == null) {
m_proxyCollisionShapes = proxyShape;
} else {
proxyShape->m_next = m_proxyCollisionShapes;
@ -221,7 +221,7 @@ void RigidBody::recomputeMassInformation() {
m_centerOfMassLocal *= m_massInverse;
m_centerOfMassWorld = m_transform * m_centerOfMassLocal;
// Compute the total mass and inertia tensor using all the collision shapes
for (ProxyShape* shape = m_proxyCollisionShapes; shape != nullptr; shape = shape->m_next) {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != null; shape = shape->m_next) {
// Get the inertia tensor of the collision shape in its local-space
etk::Matrix3x3 inertiaTensor;
shape->getCollisionShape()->computeLocalInertiaTensor(inertiaTensor, shape->getMass());
@ -254,7 +254,7 @@ void RigidBody::updateBroadPhaseState() const {
DynamicsWorld& world = static_cast<DynamicsWorld&>(m_world);
const vec3 displacement = world.m_timeStep * m_linearVelocity;
// For all the proxy collision shapes of the body
for (ProxyShape* shape = m_proxyCollisionShapes; shape != nullptr; shape = shape->m_next) {
for (ProxyShape* shape = m_proxyCollisionShapes; shape != null; shape = shape->m_next) {
// Recompute the world-space AABB of the collision shape
AABB aabb;
EPHY_VERBOSE(" : " << aabb.getMin() << " " << aabb.getMax());

View File

@ -95,7 +95,7 @@ void CollisionDetection::reportCollisionBetweenShapes(CollisionCallback* _callba
contactPoint->getLocalPointOnBody1(),
contactPoint->getLocalPointOnBody2());
// Notify the collision callback about this new contact
if (_callback != nullptr) {
if (_callback != null) {
_callback->notifyContact(contactInfo);
}
}
@ -134,7 +134,7 @@ void CollisionDetection::computeNarrowPhase() {
// TODO : Remove all the contact manifold of the overlapping pair from the contact manifolds list of the two bodies involved
// Destroy the overlapping pair
ETK_DELETE(OverlappingPair, it->second);
it->second = nullptr;
it->second = null;
it = m_overlappingPairs.erase(it);
continue;
} else {
@ -160,7 +160,7 @@ void CollisionDetection::computeNarrowPhase() {
const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType();
NarrowPhaseAlgorithm* narrowPhaseAlgorithm = m_collisionMatrix[shape1Type][shape2Type];
// If there is no collision algorithm between those two kinds of shapes
if (narrowPhaseAlgorithm == nullptr) {
if (narrowPhaseAlgorithm == null) {
continue;
}
// Notify the narrow-phase algorithm about the overlapping pair we are going to test
@ -223,7 +223,7 @@ void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* _cal
// TODO : Remove all the contact manifold of the overlapping pair from the contact manifolds list of the two bodies involved
// Destroy the overlapping pair
ETK_DELETE(OverlappingPair, it->second);
it->second = nullptr;
it->second = null;
it = m_overlappingPairs.erase(it);
continue;
} else {
@ -250,7 +250,7 @@ void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* _cal
const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType();
NarrowPhaseAlgorithm* narrowPhaseAlgorithm = m_collisionMatrix[shape1Type][shape2Type];
// If there is no collision algorithm between those two kinds of shapes
if (narrowPhaseAlgorithm == nullptr) {
if (narrowPhaseAlgorithm == null) {
continue;
}
// Notify the narrow-phase algorithm about the overlapping pair we are going to test
@ -295,7 +295,7 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* _shape1, Pr
_shape2->getCollisionShape()->getType());
// Create the overlapping pair and add it int32_to the set of overlapping pairs
OverlappingPair* newPair = ETK_NEW(OverlappingPair, _shape1, _shape2, nbMaxManifolds);
assert(newPair != nullptr);
assert(newPair != null);
m_overlappingPairs.set(pairID, newPair);
// Wake up the two bodies
_shape1->getBody()->setIsSleeping(false);
@ -311,7 +311,7 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* _proxyShape) {
// TODO : Remove all the contact manifold of the overlapping pair from the contact manifolds list of the two bodies involved
// Destroy the overlapping pair
ETK_DELETE(OverlappingPair, it->second);
it->second = nullptr;
it->second = null;
it = m_overlappingPairs.erase(it);
} else {
++it;
@ -359,7 +359,7 @@ void CollisionDetection::addAllContactManifoldsToBodies() {
}
void CollisionDetection::addContactManifoldToBody(OverlappingPair* _pair) {
assert(_pair != nullptr);
assert(_pair != null);
CollisionBody* body1 = _pair->getShape1()->getBody();
CollisionBody* body2 = _pair->getShape2()->getBody();
const ContactManifoldSet& manifoldSet = _pair->getContactManifoldSet();

View File

@ -59,7 +59,7 @@ void ContactManifold::removeContactPoint(uint32_t index) {
// Call the destructor explicitly and tell the memory allocator that
// the corresponding memory block is now free
ETK_DELETE(ContactPoint, m_contactPoints[index]);
m_contactPoints[index] = nullptr;
m_contactPoints[index] = null;
// If we don't remove the last index
if (index < m_nbContactPoints - 1) {
m_contactPoints[index] = m_contactPoints[m_nbContactPoints - 1];
@ -187,7 +187,7 @@ void ContactManifold::clear() {
// Call the destructor explicitly and tell the memory allocator that
// the corresponding memory block is now free
ETK_DELETE(ContactPoint, m_contactPoints[iii]);
m_contactPoints[iii] = nullptr;
m_contactPoints[iii] = null;
}
m_nbContactPoints = 0;
}

View File

@ -77,7 +77,7 @@ void ContactManifoldSet::addContactPoint(ContactPoint* contact) {
if (smallestDepthIndex == -1) {
// Delete the new contact
ETK_DELETE(ContactPoint, contact);
contact = nullptr;
contact = null;
return;
}
assert(smallestDepthIndex >= 0 && smallestDepthIndex < m_nbManifolds);
@ -164,7 +164,7 @@ void ContactManifoldSet::removeManifold(int32_t index) {
assert(index >= 0 && index < m_nbManifolds);
// Delete the new contact
ETK_DELETE(ContactManifold, m_manifolds[index]);
m_manifolds[index] = nullptr;
m_manifolds[index] = null;
for (int32_t i=index; (i+1) < m_nbManifolds; i++) {
m_manifolds[i] = m_manifolds[i+1];
}

View File

@ -36,8 +36,8 @@ namespace ephysics {
RaycastInfo() :
meshSubpart(-1),
triangleIndex(-1),
body(nullptr),
proxyShape(nullptr) {
body(null),
proxyShape(null) {
}

View File

@ -471,8 +471,8 @@ int32_t DynamicAABBTree::balanceSubTreeAtNode(int32_t _nodeID) {
/// Report all shapes overlapping with the AABB given in parameter.
void DynamicAABBTree::reportAllShapesOverlappingWithAABB(const AABB& _aabb, etk::Function<void(int32_t nodeId)> _callback) const {
if (_callback == nullptr) {
EPHY_ERROR("call with nullptr callback");
if (_callback == null) {
EPHY_ERROR("call with null callback");
return;
}
// Create a stack with the nodes to visit
@ -507,8 +507,8 @@ void DynamicAABBTree::reportAllShapesOverlappingWithAABB(const AABB& _aabb, etk:
// Ray casting method
void DynamicAABBTree::raycast(const ephysics::Ray& _ray, etk::Function<float(int32_t _nodeId, const ephysics::Ray& _ray)> _callback) const {
PROFILE("DynamicAABBTree::raycast()");
if (_callback == nullptr) {
EPHY_ERROR("call with nullptr callback");
if (_callback == null) {
EPHY_ERROR("call with null callback");
return;
}
float maxFraction = _ray.maxFraction;

View File

@ -71,7 +71,7 @@ void ConvexVsTriangleCallback::testTriangle(const vec3* _trianglePoints) {
// Select the collision algorithm to use between the triangle and the convex shape
NarrowPhaseAlgorithm* algo = m_collisionDetection->getCollisionAlgorithm(triangleShape.getType(), m_convexShape->getType());
// If there is no collision algorithm between those two kinds of shapes
if (algo == nullptr) {
if (algo == null) {
return;
}
// Notify the narrow-phase algorithm about the overlapping pair we are going to test

View File

@ -42,6 +42,6 @@ NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int32_t _type1,
// Convex vs Convex algorithm (GJK algorithm)
return &m_GJKAlgorithm;
} else {
return nullptr;
return null;
}
}

View File

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

View File

@ -54,7 +54,7 @@ bool EdgeEPA::computeSilhouette(const vec3* _vertices, uint32_t _indexNewVertex,
getTargetVertexIndex(),
getSourceVertexIndex());
// If the triangle has been created
if (triangle != nullptr) {
if (triangle != null) {
halfLink(EdgeEPA(triangle, 1), *this);
return true;
}
@ -71,7 +71,7 @@ bool EdgeEPA::computeSilhouette(const vec3* _vertices, uint32_t _indexNewVertex,
getTargetVertexIndex(),
getSourceVertexIndex());
// If the triangle has been created
if (triangle != nullptr) {
if (triangle != null) {
halfLink(EdgeEPA(triangle, 1), *this);
return true;
}

View File

@ -11,7 +11,7 @@
using namespace ephysics;
NarrowPhaseAlgorithm::NarrowPhaseAlgorithm():
m_currentOverlappingPair(nullptr) {
m_currentOverlappingPair(null) {
}

View File

@ -41,11 +41,11 @@ void ConcaveMeshShape::initBVHTree() {
}
void ConcaveMeshShape::getTriangleVerticesWithIndexPointer(int32_t _subPart, int32_t _triangleIndex, vec3* _outTriangleVertices) const {
EPHY_ASSERT(_outTriangleVertices != nullptr, "Input check error");
EPHY_ASSERT(_outTriangleVertices != null, "Input check error");
// Get the triangle vertex array of the current sub-part
TriangleVertexArray* triangleVertexArray = m_triangleMesh->getSubpart(_subPart);
if (triangleVertexArray == nullptr) {
EPHY_ERROR("get nullptr ...");
if (triangleVertexArray == null) {
EPHY_ERROR("get null ...");
}
ephysics::Triangle trianglePoints = triangleVertexArray->getTriangle(_triangleIndex);
_outTriangleVertices[0] = trianglePoints[0] * m_scaling;

View File

@ -74,9 +74,9 @@ ConvexMeshShape::ConvexMeshShape(float _margin):
vec3 ConvexMeshShape::getLocalSupportPointWithoutMargin(const vec3& _direction,
void** _cachedCollisionData) const {
assert(m_numberVertices == m_vertices.size());
assert(_cachedCollisionData != nullptr);
assert(_cachedCollisionData != null);
// Allocate memory for the cached collision data if not allocated yet
if ((*_cachedCollisionData) == nullptr) {
if ((*_cachedCollisionData) == null) {
*_cachedCollisionData = (int32_t*) malloc(sizeof(int32_t));
*((int32_t*)(*_cachedCollisionData)) = 0;
}

View File

@ -51,10 +51,10 @@ namespace ephysics {
}
ContactPointInfo():
shape1(nullptr),
shape2(nullptr),
collisionShape1(nullptr),
collisionShape2(nullptr) {
shape1(null),
shape2(null),
collisionShape1(null),
collisionShape2(null) {
// TODO: add it for etk::Vector
}
};

View File

@ -15,8 +15,8 @@ Joint::Joint(const JointInfo& jointInfo)
m_positionCorrectionTechnique(jointInfo.positionCorrectionTechnique),
m_isCollisionEnabled(jointInfo.isCollisionEnabled), m_isAlreadyInIsland(false) {
assert(m_body1 != nullptr);
assert(m_body2 != nullptr);
assert(m_body1 != null);
assert(m_body2 != null);
}
Joint::~Joint() {

View File

@ -50,8 +50,8 @@ namespace ephysics {
bool isCollisionEnabled; //!< True if the two bodies of the joint are allowed to collide with each other
/// Constructor
JointInfo(JointType _constraintType):
body1(nullptr),
body2(nullptr),
body1(null),
body2(null),
type(_constraintType),
positionCorrectionTechnique(NON_LINEAR_GAUSS_SEIDEL),
isCollisionEnabled(true) {

View File

@ -15,7 +15,7 @@ using namespace std;
CollisionWorld::CollisionWorld() :
m_collisionDetection(this),
m_currentBodyID(0),
m_eventListener(nullptr) {
m_eventListener(null) {
}
@ -33,7 +33,7 @@ CollisionBody* CollisionWorld::createCollisionBody(const etk::Transform3D& _tran
EPHY_ASSERT(bodyID < UINT64_MAX, "index too big");
// Create the collision body
CollisionBody* collisionBody = ETK_NEW(CollisionBody, _transform, *this, bodyID);
EPHY_ASSERT(collisionBody != nullptr, "empty Body collision");
EPHY_ASSERT(collisionBody != null, "empty Body collision");
// Add the collision body to the world
m_bodies.add(collisionBody);
// Return the pointer to the rigid body
@ -48,7 +48,7 @@ void CollisionWorld::destroyCollisionBody(CollisionBody* _collisionBody) {
// Remove the collision body from the list of bodies
m_bodies.erase(m_bodies.find(_collisionBody));
ETK_DELETE(CollisionBody, _collisionBody);
_collisionBody = nullptr;
_collisionBody = null;
}
bodyindex CollisionWorld::computeNextAvailableBodyID() {
@ -115,7 +115,7 @@ void CollisionWorld::testCollision(const CollisionBody* _body, CollisionCallback
etk::Set<uint32_t> shapes1;
// For each shape of the body
for (const ProxyShape* shape = _body->getProxyShapesList();
shape != nullptr;
shape != null;
shape = shape->getNext()) {
shapes1.add(shape->m_broadPhaseID);
}
@ -130,13 +130,13 @@ void CollisionWorld::testCollision(const CollisionBody* _body1, const CollisionB
// Create the sets of shapes
etk::Set<uint32_t> shapes1;
for (const ProxyShape* shape = _body1->getProxyShapesList();
shape != nullptr;
shape != null;
shape = shape->getNext()) {
shapes1.add(shape->m_broadPhaseID);
}
etk::Set<uint32_t> shapes2;
for (const ProxyShape* shape = _body2->getProxyShapesList();
shape != nullptr;
shape != null;
shape = shape->getNext()) {
shapes2.add(shape->m_broadPhaseID);
}

View File

@ -20,7 +20,7 @@ ConstraintSolver::ConstraintSolver(const etk::Map<RigidBody*, uint32_t>& _mapBod
void ConstraintSolver::initializeForIsland(float _dt, Island* _island) {
PROFILE("ConstraintSolver::initializeForIsland()");
assert(_island != nullptr);
assert(_island != null);
assert(_island->getNbBodies() > 0);
assert(_island->getNbJoints() > 0);
// Set the current time step
@ -42,7 +42,7 @@ void ConstraintSolver::initializeForIsland(float _dt, Island* _island) {
void ConstraintSolver::solveVelocityConstraints(Island* _island) {
PROFILE("ConstraintSolver::solveVelocityConstraints()");
assert(_island != nullptr);
assert(_island != null);
assert(_island->getNbJoints() > 0);
// For each joint of the island
Joint** joints = _island->getJoints();
@ -53,7 +53,7 @@ void ConstraintSolver::solveVelocityConstraints(Island* _island) {
void ConstraintSolver::solvePositionConstraints(Island* _island) {
PROFILE("ConstraintSolver::solvePositionConstraints()");
assert(_island != nullptr);
assert(_island != null);
assert(_island->getNbJoints() > 0);
Joint** joints = _island->getJoints();
for (uint32_t iii=0; iii < _island->getNbJoints(); ++iii) {
@ -63,16 +63,16 @@ void ConstraintSolver::solvePositionConstraints(Island* _island) {
void ConstraintSolver::setConstrainedVelocitiesArrays(vec3* _constrainedLinearVelocities,
vec3* _constrainedAngularVelocities) {
assert(_constrainedLinearVelocities != nullptr);
assert(_constrainedAngularVelocities != nullptr);
assert(_constrainedLinearVelocities != null);
assert(_constrainedAngularVelocities != null);
m_constraintSolverData.linearVelocities = _constrainedLinearVelocities;
m_constraintSolverData.angularVelocities = _constrainedAngularVelocities;
}
void ConstraintSolver::setConstrainedPositionsArrays(vec3* _constrainedPositions,
etk::Quaternion* _constrainedOrientations) {
assert(_constrainedPositions != nullptr);
assert(_constrainedOrientations != nullptr);
assert(_constrainedPositions != null);
assert(_constrainedOrientations != null);
m_constraintSolverData.positions = _constrainedPositions;
m_constraintSolverData.orientations = _constrainedOrientations;
}

View File

@ -30,10 +30,10 @@ namespace ephysics {
bool isWarmStartingActive; //!< True if warm starting of the solver is active
/// Constructor
ConstraintSolverData(const etk::Map<RigidBody*, uint32_t>& refMapBodyToConstrainedVelocityIndex):
linearVelocities(nullptr),
angularVelocities(nullptr),
positions(nullptr),
orientations(nullptr),
linearVelocities(null),
angularVelocities(null),
positions(null),
orientations(null),
mapBodyToConstrainedVelocityIndex(refMapBodyToConstrainedVelocityIndex) {
}

View File

@ -18,10 +18,10 @@ const float ContactSolver::BETA_SPLIT_IMPULSE = float(0.2);
const float ContactSolver::SLOP = float(0.01);
ContactSolver::ContactSolver(const etk::Map<RigidBody*, uint32_t>& _mapBodyToVelocityIndex) :
m_splitLinearVelocities(nullptr),
m_splitAngularVelocities(nullptr),
m_linearVelocities(nullptr),
m_angularVelocities(nullptr),
m_splitLinearVelocities(null),
m_splitAngularVelocities(null),
m_linearVelocities(null),
m_angularVelocities(null),
m_mapBodyToConstrainedVelocityIndex(_mapBodyToVelocityIndex),
m_isWarmStartingActive(true),
m_isSplitImpulseActive(true),
@ -31,11 +31,11 @@ ContactSolver::ContactSolver(const etk::Map<RigidBody*, uint32_t>& _mapBodyToVel
void ContactSolver::initializeForIsland(float _dt, Island* _island) {
PROFILE("ContactSolver::initializeForIsland()");
assert(_island != nullptr);
assert(_island != null);
assert(_island->getNbBodies() > 0);
assert(_island->getNbContactManifolds() > 0);
assert(m_splitLinearVelocities != nullptr);
assert(m_splitAngularVelocities != nullptr);
assert(m_splitLinearVelocities != null);
assert(m_splitAngularVelocities != null);
// Set the current time step
m_timeStep = _dt;
m_contactConstraints.resize(_island->getNbContactManifolds());
@ -48,8 +48,8 @@ void ContactSolver::initializeForIsland(float _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 != nullptr);
assert(body2 != nullptr);
assert(body1 != null);
assert(body2 != null);
// Get the position of the two bodies
const vec3& x1 = body1->m_centerOfMassWorld;
const vec3& x2 = body2->m_centerOfMassWorld;

View File

@ -48,7 +48,7 @@ ephysics::DynamicsWorld::~DynamicsWorld() {
for (auto &it: m_islands) {
// Call the island destructor
ETK_DELETE(Island, it);
it = nullptr;
it = null;
}
m_islands.clear();
// Release the memory allocated for the bodies velocity arrays
@ -80,7 +80,7 @@ void ephysics::DynamicsWorld::update(float timeStep) {
PROFILE("ephysics::DynamicsWorld::update()");
m_timeStep = timeStep;
// Notify the event listener about the beginning of an int32_ternal tick
if (m_eventListener != nullptr) {
if (m_eventListener != null) {
m_eventListener->beginInternalTick();
}
// Reset all the contact manifolds lists of each body
@ -107,7 +107,7 @@ void ephysics::DynamicsWorld::update(float timeStep) {
updateSleepingBodies();
}
// Notify the event listener about the end of an int32_ternal tick
if (m_eventListener != nullptr) {
if (m_eventListener != null) {
m_eventListener->endInternalTick();
}
// Reset the external force and torque applied to the bodies
@ -326,7 +326,7 @@ ephysics::RigidBody* ephysics::DynamicsWorld::createRigidBody(const etk::Transfo
assert(bodyID < UINT64_MAX);
// Create the rigid body
ephysics::RigidBody* rigidBody = ETK_NEW(RigidBody, _transform, *this, bodyID);
assert(rigidBody != nullptr);
assert(rigidBody != null);
// Add the rigid body to the physics world
m_bodies.add(rigidBody);
m_rigidBodies.add(rigidBody);
@ -341,7 +341,7 @@ void ephysics::DynamicsWorld::destroyRigidBody(RigidBody* _rigidBody) {
m_freeBodiesIDs.pushBack(_rigidBody->getID());
// Destroy all the joints in which the rigid body to be destroyed is involved
for (ephysics::JointListElement* element = _rigidBody->m_jointsList;
element != nullptr;
element != null;
element = element->next) {
destroyJoint(element->joint);
}
@ -352,11 +352,11 @@ void ephysics::DynamicsWorld::destroyRigidBody(RigidBody* _rigidBody) {
m_rigidBodies.erase(m_rigidBodies.find(_rigidBody));
// Call the destructor of the rigid body
ETK_DELETE(RigidBody, _rigidBody);
_rigidBody = nullptr;
_rigidBody = null;
}
ephysics::Joint* ephysics::DynamicsWorld::createJoint(const ephysics::JointInfo& _jointInfo) {
Joint* newJoint = nullptr;
Joint* newJoint = null;
// Allocate memory to create the new joint
switch(_jointInfo.type) {
// Ball-and-Socket joint
@ -377,7 +377,7 @@ ephysics::Joint* ephysics::DynamicsWorld::createJoint(const ephysics::JointInfo&
break;
default:
assert(false);
return nullptr;
return null;
}
// If the collision between the two bodies of the constraint is disabled
if (!_jointInfo.isCollisionEnabled) {
@ -393,8 +393,8 @@ ephysics::Joint* ephysics::DynamicsWorld::createJoint(const ephysics::JointInfo&
}
void ephysics::DynamicsWorld::destroyJoint(Joint* _joint) {
if (_joint == nullptr) {
EPHY_WARNING("Request destroy nullptr joint");
if (_joint == null) {
EPHY_WARNING("Request destroy null joint");
return;
}
// If the collision between the two bodies of the constraint was disabled
@ -413,12 +413,12 @@ void ephysics::DynamicsWorld::destroyJoint(Joint* _joint) {
size_t nbBytes = _joint->getSizeInBytes();
// Call the destructor of the joint
ETK_DELETE(Joint, _joint);
_joint = nullptr;
_joint = null;
}
void ephysics::DynamicsWorld::addJointToBody(ephysics::Joint* _joint) {
if (_joint == nullptr) {
EPHY_WARNING("Request add nullptr joint");
if (_joint == null) {
EPHY_WARNING("Request add null joint");
return;
}
// Add the joint at the beginning of the linked list of joints of the first body
@ -433,7 +433,7 @@ void ephysics::DynamicsWorld::computeIslands() {
// Clear all the islands
for (auto &it: m_islands) {
ETK_DELETE(Island, it);
it = nullptr;
it = null;
}
// Call the island destructor
m_islands.clear();
@ -448,7 +448,7 @@ void ephysics::DynamicsWorld::computeIslands() {
}
// Create a stack (using an array) for the rigid bodies to visit during the Depth First Search
etk::Vector<ephysics::RigidBody*> stackBodiesToVisit;
stackBodiesToVisit.resize(nbBodies, nullptr);
stackBodiesToVisit.resize(nbBodies, null);
// For each rigid body of the world
for (etk::Set<ephysics::RigidBody*>::Iterator it = m_rigidBodies.begin(); it != m_rigidBodies.end(); ++it) {
ephysics::RigidBody* body = *it;
@ -489,7 +489,7 @@ void ephysics::DynamicsWorld::computeIslands() {
// For each contact manifold in which the current body is involded
ephysics::ContactManifoldListElement* contactElement;
for (contactElement = bodyToVisit->m_contactManifoldsList;
contactElement != nullptr;
contactElement != null;
contactElement = contactElement->next) {
ephysics::ContactManifold* contactManifold = contactElement->contactManifold;
assert(contactManifold->getNbContactPoints() > 0);
@ -516,7 +516,7 @@ void ephysics::DynamicsWorld::computeIslands() {
// For each joint in which the current body is involved
ephysics::JointListElement* jointElement;
for (jointElement = bodyToVisit->m_jointsList;
jointElement != nullptr;
jointElement != null;
jointElement = jointElement->next) {
ephysics::Joint* joint = jointElement->joint;
// Check if the current joint has already been added int32_to an island
@ -615,7 +615,7 @@ void ephysics::DynamicsWorld::testCollision(const ephysics::CollisionBody* _body
etk::Set<uint32_t> shapes1;
// For each shape of the body
for (const ProxyShape* shape = _body->getProxyShapesList();
shape != nullptr;
shape != null;
shape = shape->getNext()) {
shapes1.add(shape->m_broadPhaseID);
}
@ -627,12 +627,12 @@ void ephysics::DynamicsWorld::testCollision(const ephysics::CollisionBody* _body
void ephysics::DynamicsWorld::testCollision(const ephysics::CollisionBody* _body1, const ephysics::CollisionBody* _body2, ephysics::CollisionCallback* _callback) {
// Create the sets of shapes
etk::Set<uint32_t> shapes1;
for (const ProxyShape* shape=_body1->getProxyShapesList(); shape != nullptr;
for (const ProxyShape* shape=_body1->getProxyShapesList(); shape != null;
shape = shape->getNext()) {
shapes1.add(shape->m_broadPhaseID);
}
etk::Set<uint32_t> shapes2;
for (const ProxyShape* shape=_body2->getProxyShapesList(); shape != nullptr;
for (const ProxyShape* shape=_body2->getProxyShapesList(); shape != null;
shape = shape->getNext()) {
shapes2.add(shape->m_broadPhaseID);
}

View File

@ -266,7 +266,7 @@ namespace ephysics {
void setTimeBeforeSleep(float timeBeforeSleep);
/**
* @brief Set an event listener object to receive events callbacks.
* @note If you use nullptr as an argument, the events callbacks will be disabled.
* @note If you use null as an argument, the events callbacks will be disabled.
* @param[in] _eventListener Pointer to the event listener object that will receive
* event callbacks during the simulation
*/

View File

@ -15,7 +15,7 @@
using namespace ephysics;
// Initialization of static variables
ProfileNode Profiler::m_rootNode("Root", nullptr);
ProfileNode Profiler::m_rootNode("Root", null);
ProfileNode* Profiler::m_currentNode = &Profiler::m_rootNode;
long double Profiler::m_profilingStartTime = Timer::getCurrentSystemTime() * 1000.0;
uint32_t Profiler::m_frameCounter = 0;
@ -23,17 +23,17 @@ uint32_t Profiler::m_frameCounter = 0;
// Constructor
ProfileNode::ProfileNode(const char* name, ProfileNode* parentNode)
:m_name(name), m_numberTotalCalls(0), m_startTime(0), m_totalTime(0),
m_recursionCounter(0), m_parentNode(parentNode), m_childNode(nullptr),
m_siblingNode(nullptr) {
m_recursionCounter(0), m_parentNode(parentNode), m_childNode(null),
m_siblingNode(null) {
reset();
}
// Destructor
ProfileNode::~ProfileNode() {
ETK_DELETE(ProfileNode, m_childNode);
m_childNode = nullptr;
m_childNode = null;
ETK_DELETE(ProfileNode, m_siblingNode);
m_siblingNode = nullptr;
m_siblingNode = null;
}
// Return a pointer to a sub node with a given name
@ -41,7 +41,7 @@ ProfileNode* ProfileNode::findSubNode(const char* name) {
// Try to find the node among the child nodes
ProfileNode* child = m_childNode;
while (child != nullptr) {
while (child != null) {
if (child->m_name == name) {
return child;
}
@ -95,12 +95,12 @@ void ProfileNode::reset() {
m_totalTime = 0.0;
// Reset the child node
if (m_childNode != nullptr) {
if (m_childNode != null) {
m_childNode->reset();
}
// Reset the sibling node
if (m_siblingNode != nullptr) {
if (m_siblingNode != null) {
m_siblingNode->reset();
}
}
@ -108,9 +108,9 @@ void ProfileNode::reset() {
// Destroy the node
void ProfileNode::destroy() {
ETK_DELETE(ProfileNode, m_childNode);
m_childNode = nullptr;
m_childNode = null;
ETK_DELETE(ProfileNode, m_siblingNode);
m_siblingNode = nullptr;
m_siblingNode = null;
}
// Constructor
@ -123,12 +123,12 @@ ProfileNodeIterator::ProfileNodeIterator(ProfileNode* startingNode)
// Enter a given child node
void ProfileNodeIterator::enterChild(int32_t index) {
m_currentChildNode = m_currentParentNode->getChildNode();
while ((m_currentChildNode != nullptr) && (index != 0)) {
while ((m_currentChildNode != null) && (index != 0)) {
index--;
m_currentChildNode = m_currentChildNode->getSiblingNode();
}
if (m_currentChildNode != nullptr) {
if (m_currentChildNode != null) {
m_currentParentNode = m_currentChildNode;
m_currentChildNode = m_currentParentNode->getChildNode();
}
@ -136,7 +136,7 @@ void ProfileNodeIterator::enterChild(int32_t index) {
// Enter a given parent node
void ProfileNodeIterator::enterParent() {
if (m_currentParentNode->getParentNode() != nullptr) {
if (m_currentParentNode->getParentNode() != null) {
m_currentParentNode = m_currentParentNode->getParentNode();
}
m_currentChildNode = m_currentParentNode->getChildNode();
@ -242,12 +242,12 @@ void Profiler::print32_tRecursiveNodeReport(ProfileNodeIterator* iterator,
// Return true if we are at the root of the profiler tree
bool ProfileNodeIterator::isRoot() {
return (m_currentParentNode->getParentNode() == nullptr);
return (m_currentParentNode->getParentNode() == null);
}
// Return true if we are at the end of a branch of the profiler tree
bool ProfileNodeIterator::isEnd() {
return (m_currentChildNode == nullptr);
return (m_currentChildNode == null);
}
// Return the name of the current node

View File

@ -29,7 +29,7 @@ class WorldRaycastCallback : public ephysics::RaycastCallback {
bool isHit;
WorldRaycastCallback() {
isHit = false;
shapeToTest = nullptr;
shapeToTest = null;
}
virtual float notifyRaycastHit(const ephysics::RaycastInfo& info) {
if (shapeToTest->getBody()->getID() == info.body->getID()) {
@ -44,9 +44,9 @@ class WorldRaycastCallback : public ephysics::RaycastCallback {
return 1.0f;
}
void reset() {
raycastInfo.body = nullptr;
raycastInfo.body = null;
raycastInfo.hitFraction = 0.0f;
raycastInfo.proxyShape = nullptr;
raycastInfo.proxyShape = null;
raycastInfo.worldNormal.setZero();
raycastInfo.worldPoint.setZero();
isHit = false;