Cache the size of lists before loops
This commit is contained in:
parent
dab4fc9143
commit
b55626df67
src
body
collision
engine
mathematics
systems
utils
|
@ -293,7 +293,8 @@ void CollisionBody::askForBroadPhaseCollisionCheck() const {
|
|||
|
||||
// For all the colliders of the body
|
||||
const Array<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
|
||||
for (uint32 i=0; i < colliderEntities.size(); i++) {
|
||||
const uint32 nbColliderEntities = colliderEntities.size();
|
||||
for (uint32 i=0; i < nbColliderEntities; i++) {
|
||||
|
||||
Collider* collider = mWorld.mCollidersComponents.getCollider(colliderEntities[i]);
|
||||
|
||||
|
@ -340,7 +341,8 @@ bool CollisionBody::raycast(const Ray& ray, RaycastInfo& raycastInfo) {
|
|||
|
||||
// For each collider of the body
|
||||
const Array<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
|
||||
for (uint32 i=0; i < colliderEntities.size(); i++) {
|
||||
const uint32 nbColliderEntities = colliderEntities.size();
|
||||
for (uint32 i=0; i < nbColliderEntities; i++) {
|
||||
|
||||
Collider* collider = mWorld.mCollidersComponents.getCollider(colliderEntities[i]);
|
||||
|
||||
|
@ -371,7 +373,8 @@ AABB CollisionBody::getAABB() const {
|
|||
collider->getCollisionShape()->computeAABB(bodyAABB, transform * collider->getLocalToBodyTransform());
|
||||
|
||||
// For each collider of the body
|
||||
for (uint32 i=1; i < colliderEntities.size(); i++) {
|
||||
const uint32 nbColliderEntities = colliderEntities.size();
|
||||
for (uint32 i=1; i < nbColliderEntities; i++) {
|
||||
|
||||
Collider* collider = mWorld.mCollidersComponents.getCollider(colliderEntities[i]);
|
||||
|
||||
|
|
|
@ -877,7 +877,8 @@ void RigidBody::resetOverlappingPairs() {
|
|||
// Get the currently overlapping pairs for this collider
|
||||
Array<uint64> overlappingPairs = mWorld.mCollidersComponents.getOverlappingPairs(colliderEntities[i]);
|
||||
|
||||
for (uint32 j=0; j < overlappingPairs.size(); j++) {
|
||||
const uint32 nbOverlappingPairs = overlappingPairs.size();
|
||||
for (uint32 j=0; j < nbOverlappingPairs; j++) {
|
||||
|
||||
mWorld.mCollisionDetection.mOverlappingPairs.removePair(overlappingPairs[j]);
|
||||
}
|
||||
|
|
|
@ -83,7 +83,8 @@ CollisionCallback::CallbackData::CallbackData(Array<reactphysics3d::ContactPair>
|
|||
mWorld(world) {
|
||||
|
||||
// Filter the contact pairs to only keep the contact events (not the overlap/trigger events)
|
||||
for (uint32 i=0; i < mContactPairs->size(); i++) {
|
||||
const uint32 nbContactPairs = mContactPairs->size();
|
||||
for (uint32 i=0; i < nbContactPairs; i++) {
|
||||
|
||||
// If the contact pair contains contacts (and is therefore not an overlap/trigger event)
|
||||
if (!(*mContactPairs)[i].isTrigger) {
|
||||
|
@ -91,7 +92,8 @@ CollisionCallback::CallbackData::CallbackData(Array<reactphysics3d::ContactPair>
|
|||
}
|
||||
}
|
||||
// Filter the lost contact pairs to only keep the contact events (not the overlap/trigger events)
|
||||
for (uint32 i=0; i < mLostContactPairs.size(); i++) {
|
||||
const uint32 nbLostContactPairs = mLostContactPairs.size();
|
||||
for (uint32 i=0; i < nbLostContactPairs; i++) {
|
||||
|
||||
// If the contact pair contains contacts (and is therefore not an overlap/trigger event)
|
||||
if (!mLostContactPairs[i].isTrigger) {
|
||||
|
|
|
@ -44,14 +44,16 @@ void HalfEdgeStructure::init() {
|
|||
Array<VerticesPair> currentFaceEdges(mAllocator, mFaces[0].faceVertices.size());
|
||||
|
||||
// For each face
|
||||
for (uint32 f=0; f<mFaces.size(); f++) {
|
||||
const uint32 nbFaces = mFaces.size();
|
||||
for (uint32 f=0; f < nbFaces; f++) {
|
||||
|
||||
Face face = mFaces[f];
|
||||
|
||||
VerticesPair firstEdgeKey(0, 0);
|
||||
|
||||
// For each vertex of the face
|
||||
for (uint32 v=0; v < face.faceVertices.size(); v++) {
|
||||
const uint32 nbFaceVertices = face.faceVertices.size();
|
||||
for (uint32 v=0; v < nbFaceVertices; v++) {
|
||||
uint32 v1Index = face.faceVertices[v];
|
||||
uint32 v2Index = face.faceVertices[v == (face.faceVertices.size() - 1) ? 0 : v + 1];
|
||||
|
||||
|
@ -107,12 +109,13 @@ void HalfEdgeStructure::init() {
|
|||
}
|
||||
|
||||
// Set next edges
|
||||
for (uint32 i=0; i < mEdges.size(); i++) {
|
||||
const uint32 nbEdges = mEdges.size();
|
||||
for (uint32 i=0; i < nbEdges; i++) {
|
||||
mEdges[i].nextEdgeIndex = mapEdgeToIndex[nextEdges[mapEdgeIndexToKey[i]]];
|
||||
}
|
||||
|
||||
// Set face edge
|
||||
for (uint32 f=0; f < mFaces.size(); f++) {
|
||||
for (uint32 f=0; f < nbFaces; f++) {
|
||||
mFaces[f].edgeIndex = mapEdgeToIndex[mapFaceIndexToEdgeKey[f]];
|
||||
}
|
||||
}
|
||||
|
|
|
@ -72,7 +72,8 @@ OverlapCallback::CallbackData::CallbackData(Array<ContactPair>& contactPairs, Ar
|
|||
mContactPairsIndices(world.mMemoryManager.getHeapAllocator()), mLostContactPairsIndices(world.mMemoryManager.getHeapAllocator()), mWorld(world) {
|
||||
|
||||
// Filter the contact pairs to only keep the overlap/trigger events (not the contact events)
|
||||
for (uint32 i=0; i < mContactPairs.size(); i++) {
|
||||
const uint32 nbContactPairs = mContactPairs.size();
|
||||
for (uint32 i=0; i < nbContactPairs; i++) {
|
||||
|
||||
// If the contact pair contains contacts (and is therefore not an overlap/trigger event)
|
||||
if (!onlyReportTriggers || mContactPairs[i].isTrigger) {
|
||||
|
@ -80,7 +81,8 @@ OverlapCallback::CallbackData::CallbackData(Array<ContactPair>& contactPairs, Ar
|
|||
}
|
||||
}
|
||||
// Filter the lost contact pairs to only keep the overlap/trigger events (not the contact events)
|
||||
for (uint32 i=0; i < mLostContactPairs.size(); i++) {
|
||||
const uint32 nbLostContactPairs = mLostContactPairs.size();
|
||||
for (uint32 i=0; i < nbLostContactPairs; i++) {
|
||||
|
||||
// If the contact pair contains contacts (and is therefore not an overlap/trigger event)
|
||||
if (!onlyReportTriggers || mLostContactPairs[i].isTrigger) {
|
||||
|
|
|
@ -166,7 +166,8 @@ decimal PolyhedronMesh::getFaceArea(uint faceIndex) const {
|
|||
Vector3 v1 = getVertex(face.faceVertices[0]);
|
||||
|
||||
// For each vertex of the face
|
||||
for (uint32 i=2; i < face.faceVertices.size(); i++) {
|
||||
const uint32 nbFaceVertices = face.faceVertices.size();
|
||||
for (uint32 i=2; i < nbFaceVertices; i++) {
|
||||
|
||||
const Vector3 v2 = getVertex(face.faceVertices[i-1]);
|
||||
const Vector3 v3 = getVertex(face.faceVertices[i]);
|
||||
|
|
|
@ -52,7 +52,8 @@ void NarrowPhaseInfoBatch::reserveMemory() {
|
|||
// Clear all the objects in the batch
|
||||
void NarrowPhaseInfoBatch::clear() {
|
||||
|
||||
for (uint32 i=0; i < narrowPhaseInfos.size(); i++) {
|
||||
const uint32 nbNarrowPhaseInfos = narrowPhaseInfos.size();
|
||||
for (uint32 i=0; i < nbNarrowPhaseInfos; i++) {
|
||||
|
||||
assert(narrowPhaseInfos[i].nbContactPoints == 0);
|
||||
|
||||
|
|
|
@ -430,7 +430,8 @@ bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI
|
|||
bool contactFound = false;
|
||||
|
||||
// For each of the two clipped points
|
||||
for (uint32 i = 0; i<clipSegment.size(); i++) {
|
||||
const uint32 nbClipSegments = clipSegment.size();
|
||||
for (uint32 i = 0; i < nbClipSegments; i++) {
|
||||
|
||||
// Compute the penetration depth of the two clipped points (to filter out the points that does not correspond to the penetration depth)
|
||||
const decimal clipPointPenDepth = (planesPoints[0] - clipSegment[i]).dot(faceNormal);
|
||||
|
@ -915,13 +916,13 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene
|
|||
// Get the incident face
|
||||
const HalfEdgeStructure::Face& incidentFace = incidentPolyhedron->getFace(incidentFaceIndex);
|
||||
|
||||
uint32 nbIncidentFaceVertices = incidentFace.faceVertices.size();
|
||||
const uint32 nbIncidentFaceVertices = incidentFace.faceVertices.size();
|
||||
Array<Vector3> polygonVertices(mMemoryAllocator, nbIncidentFaceVertices); // Vertices to clip of the incident face
|
||||
Array<Vector3> planesNormals(mMemoryAllocator, nbIncidentFaceVertices); // Normals of the clipping planes
|
||||
Array<Vector3> planesPoints(mMemoryAllocator, nbIncidentFaceVertices); // Points on the clipping planes
|
||||
|
||||
// Get all the vertices of the incident face (in the reference local-space)
|
||||
for (uint32 i=0; i < incidentFace.faceVertices.size(); i++) {
|
||||
for (uint32 i=0; i < nbIncidentFaceVertices; i++) {
|
||||
const Vector3 faceVertexIncidentSpace = incidentPolyhedron->getVertexPosition(incidentFace.faceVertices[i]);
|
||||
polygonVertices.add(incidentToReferenceTransform * faceVertexIncidentSpace);
|
||||
}
|
||||
|
@ -963,7 +964,8 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene
|
|||
// We only keep the clipped points that are below the reference face
|
||||
const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(referencePolyhedron->getHalfEdge(firstEdgeIndex).vertexIndex);
|
||||
bool contactPointsFound = false;
|
||||
for (uint32 i=0; i<clipPolygonVertices.size(); i++) {
|
||||
const uint32 nbClipPolygonVertices = clipPolygonVertices.size();
|
||||
for (uint32 i=0; i < nbClipPolygonVertices; i++) {
|
||||
|
||||
// Compute the penetration depth of this contact point (can be different from the minPenetration depth which is
|
||||
// the maximal penetration depth of any contact point for this separating axis
|
||||
|
|
|
@ -96,7 +96,8 @@ void CollisionShape::computeAABB(AABB& aabb, const Transform& transform) const {
|
|||
/// Notify all the assign colliders that the size of the collision shape has changed
|
||||
void CollisionShape::notifyColliderAboutChangedSize() {
|
||||
|
||||
for (uint32 i=0; i < mColliders.size(); i++) {
|
||||
const uint32 nbColliders = mColliders.size();
|
||||
for (uint32 i=0; i < nbColliders; i++) {
|
||||
mColliders[i]->setHasCollisionShapeChangedSize(true);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -250,7 +250,8 @@ bool HeightFieldShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collide
|
|||
decimal smallestHitFraction = ray.maxFraction;
|
||||
|
||||
// For each overlapping triangle
|
||||
for (uint32 i=0; i < shapeIds.size(); i++)
|
||||
const uint32 nbShapeIds = shapeIds.size();
|
||||
for (uint32 i=0; i < nbShapeIds; i++)
|
||||
{
|
||||
// Create a triangle collision shape
|
||||
TriangleShape triangleShape(&(triangleVertices[i * 3]), &(triangleVerticesNormals[i * 3]), shapeIds[i], allocator);
|
||||
|
|
|
@ -239,7 +239,8 @@ void PhysicsWorld::setBodyDisabled(Entity bodyEntity, bool isDisabled) {
|
|||
|
||||
// For each collider of the body
|
||||
const Array<Entity>& collidersEntities = mCollisionBodyComponents.getColliders(bodyEntity);
|
||||
for (uint32 i=0; i < collidersEntities.size(); i++) {
|
||||
const uint32 nbColliderEntities = collidersEntities.size();
|
||||
for (uint32 i=0; i < nbColliderEntities; i++) {
|
||||
|
||||
mCollidersComponents.setIsEntityDisabled(collidersEntities[i], isDisabled);
|
||||
}
|
||||
|
@ -247,7 +248,8 @@ void PhysicsWorld::setBodyDisabled(Entity bodyEntity, bool isDisabled) {
|
|||
// Disable the joints of the body if necessary
|
||||
// For each joint of the body
|
||||
const Array<Entity>& joints = mRigidBodyComponents.getJoints(bodyEntity);
|
||||
for(uint32 i=0; i < joints.size(); i++) {
|
||||
const uint32 nbJoints = joints.size();
|
||||
for(uint32 i=0; i < nbJoints; i++) {
|
||||
|
||||
const Entity body1Entity = mJointsComponents.getBody1Entity(joints[i]);
|
||||
const Entity body2Entity = mJointsComponents.getBody2Entity(joints[i]);
|
||||
|
@ -519,7 +521,8 @@ void PhysicsWorld::destroyRigidBody(RigidBody* rigidBody) {
|
|||
|
||||
// Destroy all the joints in which the rigid body to be destroyed is involved
|
||||
const Array<Entity>& joints = mRigidBodyComponents.getJoints(rigidBody->getEntity());
|
||||
for (uint32 i=0; i < joints.size(); i++) {
|
||||
const uint32 nbJoints = joints.size();
|
||||
for (uint32 i=0; i < nbJoints; i++) {
|
||||
destroyJoint(mJointsComponents.getJoint(joints[i]));
|
||||
}
|
||||
|
||||
|
@ -829,7 +832,8 @@ void PhysicsWorld::createIslands() {
|
|||
|
||||
// If the body is involved in contacts with other bodies
|
||||
// For each contact pair in which the current body is involded
|
||||
for (uint32 p=0; p < mRigidBodyComponents.mContactPairs[bodyToVisitIndex].size(); p++) {
|
||||
const uint32 nbBodyContactPairs = mRigidBodyComponents.mContactPairs[bodyToVisitIndex].size();
|
||||
for (uint32 p=0; p < nbBodyContactPairs; p++) {
|
||||
|
||||
const uint32 contactPairIndex = mRigidBodyComponents.mContactPairs[bodyToVisitIndex][p];
|
||||
ContactPair& pair = (*mCollisionDetection.mCurrentContactPairs)[contactPairIndex];
|
||||
|
@ -869,7 +873,8 @@ void PhysicsWorld::createIslands() {
|
|||
|
||||
// For each joint in which the current body is involved
|
||||
const Array<Entity>& joints = mRigidBodyComponents.getJoints(rigidBodyToVisit->getEntity());
|
||||
for (uint32 i=0; i < joints.size(); i++) {
|
||||
const uint32 nbBodyJoints = joints.size();
|
||||
for (uint32 i=0; i < nbBodyJoints; i++) {
|
||||
|
||||
// Check if the current joint has already been added into an island
|
||||
if (mJointsComponents.getIsAlreadyInIsland(joints[i])) continue;
|
||||
|
@ -894,7 +899,8 @@ void PhysicsWorld::createIslands() {
|
|||
|
||||
// Reset the isAlreadyIsland variable of the static bodies so that they
|
||||
// can also be included in the other islands
|
||||
for (uint32 j=0; j < staticBodiesAddedToIsland.size(); j++) {
|
||||
const uint32 nbStaticBodiesAddedToIsland = staticBodiesAddedToIsland.size();
|
||||
for (uint32 j=0; j < nbStaticBodiesAddedToIsland; j++) {
|
||||
|
||||
assert(mRigidBodyComponents.getBodyType(staticBodiesAddedToIsland[j]) == BodyType::STATIC);
|
||||
mRigidBodyComponents.setIsAlreadyInIsland(staticBodiesAddedToIsland[j], false);
|
||||
|
|
|
@ -234,7 +234,8 @@ Array<Vector3> reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, const
|
|||
inputVertices.add(segB);
|
||||
|
||||
// For each clipping plane
|
||||
for (uint32 p=0; p<planesPoints.size(); p++) {
|
||||
const uint32 nbPlanesPoints = planesPoints.size();
|
||||
for (uint32 p=0; p < nbPlanesPoints; p++) {
|
||||
|
||||
// If there is no more vertices, stop
|
||||
if (inputVertices.size() == 0) return inputVertices;
|
||||
|
@ -308,7 +309,8 @@ Array<Vector3> reactphysics3d::clipPolygonWithPlanes(const Array<Vector3>& polyg
|
|||
inputVertices.addRange(polygonVertices);
|
||||
|
||||
// For each clipping plane
|
||||
for (uint32 p=0; p<planesPoints.size(); p++) {
|
||||
const uint32 nbPlanesPoints = planesPoints.size();
|
||||
for (uint32 p=0; p < nbPlanesPoints; p++) {
|
||||
|
||||
outputVertices.clear();
|
||||
|
||||
|
|
|
@ -647,7 +647,8 @@ void CollisionDetectionSystem::addContactPairsToBodies() {
|
|||
void CollisionDetectionSystem::computeMapPreviousContactPairs() {
|
||||
|
||||
mPreviousMapPairIdToContactPairIndex.clear();
|
||||
for (uint32 i=0; i < mCurrentContactPairs->size(); i++) {
|
||||
const uint32 nbCurrentContactPairs = mCurrentContactPairs->size();
|
||||
for (uint32 i=0; i < nbCurrentContactPairs; i++) {
|
||||
mPreviousMapPairIdToContactPairIndex.add(Pair<uint64, uint>((*mCurrentContactPairs)[i].pairId, i));
|
||||
}
|
||||
}
|
||||
|
@ -984,7 +985,8 @@ void CollisionDetectionSystem::createSnapshotContacts(Array<ContactPair>& contac
|
|||
void CollisionDetectionSystem::initContactsWithPreviousOnes() {
|
||||
|
||||
// For each contact pair of the current frame
|
||||
for (uint32 i=0; i < mCurrentContactPairs->size(); i++) {
|
||||
const uint32 nbCurrentContactPairs = mCurrentContactPairs->size();
|
||||
for (uint32 i=0; i < nbCurrentContactPairs; i++) {
|
||||
|
||||
ContactPair& currentContactPair = (*mCurrentContactPairs)[i];
|
||||
|
||||
|
|
|
@ -280,7 +280,8 @@ void DebugRenderer::drawConvexMesh(const Transform& transform, const ConvexMeshS
|
|||
assert(face.faceVertices.size() >= 3);
|
||||
|
||||
// Perform a fan triangulation of the convex polygon face
|
||||
for (uint32 v = 2; v < face.faceVertices.size(); v++) {
|
||||
const uint32 nbFaceVertices = face.faceVertices.size();
|
||||
for (uint32 v = 2; v < nbFaceVertices; v++) {
|
||||
|
||||
uint v1Index = face.faceVertices[v - 2];
|
||||
uint v2Index = face.faceVertices[v - 1];
|
||||
|
|
Loading…
Reference in New Issue
Block a user