Replace some uint declarations to uint32
This commit is contained in:
parent
f65cc68915
commit
90741a69bb
|
@ -137,10 +137,10 @@ class CollisionBody {
|
|||
AABB getAABB() const;
|
||||
|
||||
/// Return a const pointer to a given collider of the body
|
||||
const Collider* getCollider(uint colliderIndex) const;
|
||||
const Collider* getCollider(uint32 colliderIndex) const;
|
||||
|
||||
/// Return a pointer to a given collider of the body
|
||||
Collider* getCollider(uint colliderIndex);
|
||||
Collider* getCollider(uint32 colliderIndex);
|
||||
|
||||
/// Return the number of colliders associated with this body
|
||||
uint32 getNbColliders() const;
|
||||
|
|
|
@ -63,7 +63,7 @@ class ContactManifold {
|
|||
// -------------------- Attributes -------------------- //
|
||||
|
||||
/// Index of the first contact point of the manifold in the array of contact points
|
||||
uint contactPointsIndex;
|
||||
uint32 contactPointsIndex;
|
||||
|
||||
/// Entity of the first body in contact
|
||||
Entity bodyEntity1;
|
||||
|
|
|
@ -51,7 +51,7 @@ struct ContactPair {
|
|||
uint64 pairId;
|
||||
|
||||
/// Indices of the potential contact manifolds
|
||||
Array<uint> potentialContactManifoldsIndices;
|
||||
Array<uint32> potentialContactManifoldsIndices;
|
||||
|
||||
/// Entity of the first body of the contact
|
||||
Entity body1Entity;
|
||||
|
@ -93,7 +93,7 @@ struct ContactPair {
|
|||
|
||||
/// Constructor
|
||||
ContactPair(uint64 pairId, Entity body1Entity, Entity body2Entity, Entity collider1Entity,
|
||||
Entity collider2Entity, uint contactPairIndex, bool collidingInPreviousFrame, bool isTrigger, MemoryAllocator& allocator)
|
||||
Entity collider2Entity, uint32 contactPairIndex, bool collidingInPreviousFrame, bool isTrigger, MemoryAllocator& allocator)
|
||||
: allocator(allocator), pairId(pairId), potentialContactManifoldsIndices(allocator, 1),
|
||||
body1Entity(body1Entity), body2Entity(body2Entity),
|
||||
collider1Entity(collider1Entity), collider2Entity(collider2Entity),
|
||||
|
@ -103,7 +103,7 @@ struct ContactPair {
|
|||
}
|
||||
|
||||
// Remove a potential manifold at a given index in the array
|
||||
void removePotentialManifoldAtIndex(uint index) {
|
||||
void removePotentialManifoldAtIndex(uint32 index) {
|
||||
assert(index < potentialContactManifoldsIndices.size());
|
||||
|
||||
potentialContactManifoldsIndices.removeAtAndReplaceByLast(index);
|
||||
|
|
|
@ -100,7 +100,7 @@ class HalfEdgeStructure {
|
|||
void init();
|
||||
|
||||
/// Add a vertex
|
||||
uint32 addVertex(uint vertexPointIndex);
|
||||
uint32 addVertex(uint32 vertexPointIndex);
|
||||
|
||||
/// Add a face
|
||||
void addFace(Array<uint32> faceVertices);
|
||||
|
|
|
@ -135,7 +135,7 @@ struct NarrowPhaseInfoBatch {
|
|||
const Vector3& localPt1, const Vector3& localPt2);
|
||||
|
||||
/// Reset the remaining contact points
|
||||
void resetContactPoints(uint index);
|
||||
void resetContactPoints(uint32 index);
|
||||
|
||||
// Initialize the containers using cached capacity
|
||||
void reserveMemory();
|
||||
|
@ -159,7 +159,7 @@ RP3D_FORCE_INLINE void NarrowPhaseInfoBatch::addNarrowPhaseInfo(uint64 pairId, E
|
|||
}
|
||||
|
||||
// Add a new contact point
|
||||
RP3D_FORCE_INLINE void NarrowPhaseInfoBatch::addContactPoint(uint index, const Vector3& contactNormal, decimal penDepth, const Vector3& localPt1, const Vector3& localPt2) {
|
||||
RP3D_FORCE_INLINE void NarrowPhaseInfoBatch::addContactPoint(uint32 index, const Vector3& contactNormal, decimal penDepth, const Vector3& localPt1, const Vector3& localPt2) {
|
||||
|
||||
assert(penDepth > decimal(0.0));
|
||||
|
||||
|
@ -177,7 +177,7 @@ RP3D_FORCE_INLINE void NarrowPhaseInfoBatch::addContactPoint(uint index, const V
|
|||
}
|
||||
|
||||
// Reset the remaining contact points
|
||||
RP3D_FORCE_INLINE void NarrowPhaseInfoBatch::resetContactPoints(uint index) {
|
||||
RP3D_FORCE_INLINE void NarrowPhaseInfoBatch::resetContactPoints(uint32 index) {
|
||||
narrowPhaseInfos[index].nbContactPoints = 0;
|
||||
}
|
||||
|
||||
|
|
|
@ -107,7 +107,7 @@ class SATAlgorithm {
|
|||
decimal testSingleFaceDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1,
|
||||
const ConvexPolyhedronShape* polyhedron2,
|
||||
const Transform& polyhedron1ToPolyhedron2,
|
||||
uint faceIndex) const;
|
||||
uint32 faceIndex) const;
|
||||
|
||||
|
||||
/// Test all the normals of a polyhedron for separating axis in the polyhedron vs polyhedron case
|
||||
|
@ -115,11 +115,11 @@ class SATAlgorithm {
|
|||
const Transform& polyhedron1ToPolyhedron2, uint& minFaceIndex) const;
|
||||
|
||||
/// Compute the penetration depth between a face of the polyhedron and a sphere along the polyhedron face normal direction
|
||||
decimal computePolyhedronFaceVsSpherePenetrationDepth(uint faceIndex, const ConvexPolyhedronShape* polyhedron,
|
||||
decimal computePolyhedronFaceVsSpherePenetrationDepth(uint32 faceIndex, const ConvexPolyhedronShape* polyhedron,
|
||||
const SphereShape* sphere, const Vector3& sphereCenter) const;
|
||||
|
||||
/// Compute the penetration depth between the face of a polyhedron and a capsule along the polyhedron face normal direction
|
||||
decimal computePolyhedronFaceVsCapsulePenetrationDepth(uint polyhedronFaceIndex, const ConvexPolyhedronShape* polyhedron,
|
||||
decimal computePolyhedronFaceVsCapsulePenetrationDepth(uint32 polyhedronFaceIndex, const ConvexPolyhedronShape* polyhedron,
|
||||
const CapsuleShape* capsule, const Transform& polyhedronToCapsuleTransform,
|
||||
Vector3& outFaceNormalCapsuleSpace) const;
|
||||
|
||||
|
@ -132,8 +132,8 @@ class SATAlgorithm {
|
|||
/// Compute the contact points between two faces of two convex polyhedra.
|
||||
bool computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPenetrationFaceNormalPolyhedron1, const ConvexPolyhedronShape* polyhedron1,
|
||||
const ConvexPolyhedronShape* polyhedron2, const Transform& polyhedron1ToPolyhedron2,
|
||||
const Transform& polyhedron2ToPolyhedron1, uint minFaceIndex,
|
||||
NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchIndex) const;
|
||||
const Transform& polyhedron2ToPolyhedron1, uint32 minFaceIndex,
|
||||
NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint32 batchIndex) const;
|
||||
|
||||
|
||||
public :
|
||||
|
@ -154,24 +154,24 @@ class SATAlgorithm {
|
|||
|
||||
/// Test collision between a sphere and a convex mesh
|
||||
bool testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch,
|
||||
uint batchStartIndex, uint batchNbItems) const;
|
||||
uint32 batchStartIndex, uint32 batchNbItems) const;
|
||||
|
||||
/// Test collision between a capsule and a convex mesh
|
||||
bool testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchIndex) const;
|
||||
bool testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint32 batchIndex) const;
|
||||
|
||||
/// Compute the two contact points between a polyhedron and a capsule when the separating axis is a face normal of the polyhedron
|
||||
bool computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron,
|
||||
bool computeCapsulePolyhedronFaceContactPoints(uint32 referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron,
|
||||
decimal penetrationDepth, const Transform& polyhedronToCapsuleTransform,
|
||||
Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace,
|
||||
const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace,
|
||||
NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchIndex, bool isCapsuleShape1) const;
|
||||
NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint32 batchIndex, bool isCapsuleShape1) const;
|
||||
|
||||
// This method returns true if an edge of a polyhedron and a capsule forms a face of the Minkowski Difference
|
||||
bool isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, const Vector3& edgeAdjacentFace1Normal,
|
||||
const Vector3& edgeAdjacentFace2Normal) const;
|
||||
|
||||
/// Test collision between two convex meshes
|
||||
bool testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex, uint batchNbItems) const;
|
||||
bool testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint32 batchStartIndex, uint32 batchNbItems) const;
|
||||
|
||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||
|
||||
|
|
|
@ -65,8 +65,8 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm {
|
|||
SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm) = delete;
|
||||
|
||||
/// Compute a contact info if the two bounding volume collide
|
||||
bool testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex,
|
||||
uint batchNbItems, MemoryAllocator& memoryAllocator);
|
||||
bool testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint32 batchStartIndex,
|
||||
uint32 batchNbItems, MemoryAllocator& memoryAllocator);
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -284,7 +284,7 @@ RP3D_FORCE_INLINE bool AABB::testRayIntersect(const Vector3& rayOrigin, const Ve
|
|||
decimal tMax = std::max(t1, t2);
|
||||
tMax = std::min(tMax, rayMaxFraction);
|
||||
|
||||
for (uint i = 1; i < 3; i++) {
|
||||
for (int i = 1; i < 3; i++) {
|
||||
|
||||
t1 = (mMinCoordinates[i] - rayOrigin[i]) * rayDirectionInverse[i];
|
||||
t2 = (mMaxCoordinates[i] - rayOrigin[i]) * rayDirectionInverse[i];
|
||||
|
|
|
@ -160,17 +160,17 @@ class ConcaveMeshShape : public ConcaveShape {
|
|||
void initBVHTree();
|
||||
|
||||
/// Return the three vertices coordinates (in the array outTriangleVertices) of a triangle
|
||||
void getTriangleVertices(uint subPart, uint triangleIndex, Vector3* outTriangleVertices) const;
|
||||
void getTriangleVertices(uint32 subPart, uint32 triangleIndex, Vector3* outTriangleVertices) const;
|
||||
|
||||
/// Return the three vertex normals (in the array outVerticesNormals) of a triangle
|
||||
void getTriangleVerticesNormals(uint subPart, uint triangleIndex, Vector3* outVerticesNormals) const;
|
||||
void getTriangleVerticesNormals(uint32 subPart, uint32 triangleIndex, Vector3* outVerticesNormals) const;
|
||||
|
||||
/// Compute the shape Id for a given triangle of the mesh
|
||||
uint computeTriangleShapeId(uint subPart, uint triangleIndex) const;
|
||||
uint32 computeTriangleShapeId(uint32 subPart, uint32 triangleIndex) const;
|
||||
|
||||
/// Compute all the triangles of the mesh that are overlapping with the AABB in parameter
|
||||
virtual void computeOverlappingTriangles(const AABB& localAABB, Array<Vector3>& triangleVertices,
|
||||
Array<Vector3> &triangleVerticesNormals, Array<uint>& shapeIds,
|
||||
Array<Vector3> &triangleVerticesNormals, Array<uint32>& shapeIds,
|
||||
MemoryAllocator& allocator) const override;
|
||||
|
||||
/// Destructor
|
||||
|
@ -185,13 +185,13 @@ class ConcaveMeshShape : public ConcaveShape {
|
|||
ConcaveMeshShape& operator=(const ConcaveMeshShape& shape) = delete;
|
||||
|
||||
/// Return the number of sub parts contained in this mesh
|
||||
uint getNbSubparts() const;
|
||||
uint32 getNbSubparts() const;
|
||||
|
||||
/// Return the number of triangles in a sub part of the mesh
|
||||
uint getNbTriangles(uint subPart) const;
|
||||
uint32 getNbTriangles(uint32 subPart) const;
|
||||
|
||||
/// Return the indices of the three vertices of a given triangle in the array
|
||||
void getTriangleVerticesIndices(uint subPart, uint triangleIndex, uint* outVerticesIndices) const;
|
||||
void getTriangleVerticesIndices(uint32 subPart, uint32 triangleIndex, uint32* outVerticesIndices) const;
|
||||
|
||||
/// Return the local bounds of the shape in x, y and z directions.
|
||||
virtual void getLocalBounds(Vector3& min, Vector3& max) const override;
|
||||
|
|
|
@ -46,7 +46,7 @@ class TriangleCallback {
|
|||
virtual ~TriangleCallback() = default;
|
||||
|
||||
/// Report a triangle
|
||||
virtual void testTriangle(const Vector3* trianglePoints, const Vector3* verticesNormals, uint shapeId)=0;
|
||||
virtual void testTriangle(const Vector3* trianglePoints, const Vector3* verticesNormals, uint32 shapeId)=0;
|
||||
|
||||
};
|
||||
|
||||
|
@ -112,7 +112,7 @@ class ConcaveShape : public CollisionShape {
|
|||
|
||||
/// Use a callback method on all triangles of the concave shape inside a given AABB
|
||||
virtual void computeOverlappingTriangles(const AABB& localAABB, Array<Vector3>& triangleVertices,
|
||||
Array<Vector3>& triangleVerticesNormals, Array<uint>& shapeIds,
|
||||
Array<Vector3>& triangleVerticesNormals, Array<uint32>& shapeIds,
|
||||
MemoryAllocator& allocator) const=0;
|
||||
|
||||
/// Compute and return the volume of the collision shape
|
||||
|
|
|
@ -109,28 +109,28 @@ class ConvexMeshShape : public ConvexPolyhedronShape {
|
|||
virtual Vector3 getLocalInertiaTensor(decimal mass) const override;
|
||||
|
||||
/// Return the number of faces of the polyhedron
|
||||
virtual uint getNbFaces() const override;
|
||||
virtual uint32 getNbFaces() const override;
|
||||
|
||||
/// Return a given face of the polyhedron
|
||||
virtual const HalfEdgeStructure::Face& getFace(uint faceIndex) const override;
|
||||
virtual const HalfEdgeStructure::Face& getFace(uint32 faceIndex) const override;
|
||||
|
||||
/// Return the number of vertices of the polyhedron
|
||||
virtual uint getNbVertices() const override;
|
||||
virtual uint32 getNbVertices() const override;
|
||||
|
||||
/// Return a given vertex of the polyhedron
|
||||
virtual HalfEdgeStructure::Vertex getVertex(uint vertexIndex) const override;
|
||||
virtual HalfEdgeStructure::Vertex getVertex(uint32 vertexIndex) const override;
|
||||
|
||||
/// Return the number of half-edges of the polyhedron
|
||||
virtual uint getNbHalfEdges() const override;
|
||||
virtual uint32 getNbHalfEdges() const override;
|
||||
|
||||
/// Return a given half-edge of the polyhedron
|
||||
virtual const HalfEdgeStructure::Edge& getHalfEdge(uint edgeIndex) const override;
|
||||
virtual const HalfEdgeStructure::Edge& getHalfEdge(uint32 edgeIndex) const override;
|
||||
|
||||
/// Return the position of a given vertex
|
||||
virtual Vector3 getVertexPosition(uint vertexIndex) const override;
|
||||
virtual Vector3 getVertexPosition(uint32 vertexIndex) const override;
|
||||
|
||||
/// Return the normal vector of a given face of the polyhedron
|
||||
virtual Vector3 getFaceNormal(uint faceIndex) const override;
|
||||
virtual Vector3 getFaceNormal(uint32 faceIndex) const override;
|
||||
|
||||
/// Return the centroid of the polyhedron
|
||||
virtual Vector3 getCentroid() const override;
|
||||
|
@ -192,46 +192,46 @@ RP3D_FORCE_INLINE Vector3 ConvexMeshShape::getLocalInertiaTensor(decimal mass) c
|
|||
}
|
||||
|
||||
// Return the number of faces of the polyhedron
|
||||
RP3D_FORCE_INLINE uint ConvexMeshShape::getNbFaces() const {
|
||||
RP3D_FORCE_INLINE uint32 ConvexMeshShape::getNbFaces() const {
|
||||
return mPolyhedronMesh->getHalfEdgeStructure().getNbFaces();
|
||||
}
|
||||
|
||||
// Return a given face of the polyhedron
|
||||
RP3D_FORCE_INLINE const HalfEdgeStructure::Face& ConvexMeshShape::getFace(uint faceIndex) const {
|
||||
RP3D_FORCE_INLINE const HalfEdgeStructure::Face& ConvexMeshShape::getFace(uint32 faceIndex) const {
|
||||
assert(faceIndex < getNbFaces());
|
||||
return mPolyhedronMesh->getHalfEdgeStructure().getFace(faceIndex);
|
||||
}
|
||||
|
||||
// Return the number of vertices of the polyhedron
|
||||
RP3D_FORCE_INLINE uint ConvexMeshShape::getNbVertices() const {
|
||||
RP3D_FORCE_INLINE uint32 ConvexMeshShape::getNbVertices() const {
|
||||
return mPolyhedronMesh->getHalfEdgeStructure().getNbVertices();
|
||||
}
|
||||
|
||||
// Return a given vertex of the polyhedron
|
||||
RP3D_FORCE_INLINE HalfEdgeStructure::Vertex ConvexMeshShape::getVertex(uint vertexIndex) const {
|
||||
RP3D_FORCE_INLINE HalfEdgeStructure::Vertex ConvexMeshShape::getVertex(uint32 vertexIndex) const {
|
||||
assert(vertexIndex < getNbVertices());
|
||||
return mPolyhedronMesh->getHalfEdgeStructure().getVertex(vertexIndex);
|
||||
}
|
||||
|
||||
// Return the number of half-edges of the polyhedron
|
||||
RP3D_FORCE_INLINE uint ConvexMeshShape::getNbHalfEdges() const {
|
||||
RP3D_FORCE_INLINE uint32 ConvexMeshShape::getNbHalfEdges() const {
|
||||
return mPolyhedronMesh->getHalfEdgeStructure().getNbHalfEdges();
|
||||
}
|
||||
|
||||
// Return a given half-edge of the polyhedron
|
||||
RP3D_FORCE_INLINE const HalfEdgeStructure::Edge& ConvexMeshShape::getHalfEdge(uint edgeIndex) const {
|
||||
RP3D_FORCE_INLINE const HalfEdgeStructure::Edge& ConvexMeshShape::getHalfEdge(uint32 edgeIndex) const {
|
||||
assert(edgeIndex < getNbHalfEdges());
|
||||
return mPolyhedronMesh->getHalfEdgeStructure().getHalfEdge(edgeIndex);
|
||||
}
|
||||
|
||||
// Return the position of a given vertex
|
||||
RP3D_FORCE_INLINE Vector3 ConvexMeshShape::getVertexPosition(uint vertexIndex) const {
|
||||
RP3D_FORCE_INLINE Vector3 ConvexMeshShape::getVertexPosition(uint32 vertexIndex) const {
|
||||
assert(vertexIndex < getNbVertices());
|
||||
return mPolyhedronMesh->getVertex(vertexIndex) * mScale;
|
||||
}
|
||||
|
||||
// Return the normal vector of a given face of the polyhedron
|
||||
RP3D_FORCE_INLINE Vector3 ConvexMeshShape::getFaceNormal(uint faceIndex) const {
|
||||
RP3D_FORCE_INLINE Vector3 ConvexMeshShape::getFaceNormal(uint32 faceIndex) const {
|
||||
assert(faceIndex < getNbFaces());
|
||||
return mPolyhedronMesh->getFaceNormal(faceIndex);
|
||||
}
|
||||
|
|
|
@ -103,7 +103,7 @@ class HeightFieldShape : public ConcaveShape {
|
|||
const Vector3& scaling = Vector3(1,1,1));
|
||||
|
||||
/// Raycast a single triangle of the height-field
|
||||
bool raycastTriangle(const Ray& ray, const Vector3& p1, const Vector3& p2, const Vector3& p3, uint shapeId,
|
||||
bool raycastTriangle(const Ray& ray, const Vector3& p1, const Vector3& p2, const Vector3& p3, uint32 shapeId,
|
||||
Collider *collider, RaycastInfo& raycastInfo, decimal &smallestHitFraction, MemoryAllocator& allocator) const;
|
||||
|
||||
/// Raycast method with feedback information
|
||||
|
@ -124,7 +124,7 @@ class HeightFieldShape : public ConcaveShape {
|
|||
void computeMinMaxGridCoordinates(int* minCoords, int* maxCoords, const AABB& aabbToCollide) const;
|
||||
|
||||
/// Compute the shape Id for a given triangle
|
||||
uint computeTriangleShapeId(uint iIndex, uint jIndex, uint secondTriangleIncrement) const;
|
||||
uint32 computeTriangleShapeId(uint32 iIndex, uint32 jIndex, uint32 secondTriangleIncrement) const;
|
||||
|
||||
/// Compute the first grid cell of the heightfield intersected by a ray
|
||||
bool computeEnteringRayGridCoordinates(const Ray& ray, int& i, int& j, Vector3& outHitPoint) const;
|
||||
|
@ -160,7 +160,7 @@ class HeightFieldShape : public ConcaveShape {
|
|||
|
||||
/// Use a callback method on all triangles of the concave shape inside a given AABB
|
||||
virtual void computeOverlappingTriangles(const AABB& localAABB, Array<Vector3>& triangleVertices,
|
||||
Array<Vector3>& triangleVerticesNormals, Array<uint>& shapeIds,
|
||||
Array<Vector3>& triangleVerticesNormals, Array<uint32>& shapeIds,
|
||||
MemoryAllocator& allocator) const override;
|
||||
|
||||
/// Return the string representation of the shape
|
||||
|
@ -213,7 +213,7 @@ RP3D_FORCE_INLINE int HeightFieldShape::computeIntegerGridValue(decimal value) c
|
|||
}
|
||||
|
||||
// Compute the shape Id for a given triangle
|
||||
RP3D_FORCE_INLINE uint HeightFieldShape::computeTriangleShapeId(uint iIndex, uint jIndex, uint secondTriangleIncrement) const {
|
||||
RP3D_FORCE_INLINE uint32 HeightFieldShape::computeTriangleShapeId(uint32 iIndex, uint32 jIndex, uint32 secondTriangleIncrement) const {
|
||||
|
||||
return (jIndex * (mNbColumns - 1) + iIndex) * 2 + secondTriangleIncrement;
|
||||
}
|
||||
|
|
|
@ -107,11 +107,11 @@ class TriangleShape : public ConvexPolyhedronShape {
|
|||
Vector3& outNewLocalContactPointOtherShape, Vector3& outSmoothWorldContactTriangleNormal) const;
|
||||
|
||||
/// Constructor
|
||||
TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint shapeId, HalfEdgeStructure& triangleHalfEdgeStructure,
|
||||
TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint32 shapeId, HalfEdgeStructure& triangleHalfEdgeStructure,
|
||||
MemoryAllocator& allocator);
|
||||
|
||||
/// Constructor
|
||||
TriangleShape(const Vector3* vertices, uint shapeId, HalfEdgeStructure& triangleHalfEdgeStructure, MemoryAllocator& allocator);
|
||||
TriangleShape(const Vector3* vertices, uint32 shapeId, HalfEdgeStructure& triangleHalfEdgeStructure, MemoryAllocator& allocator);
|
||||
|
||||
/// Destructor
|
||||
virtual ~TriangleShape() override = default;
|
||||
|
@ -142,28 +142,28 @@ class TriangleShape : public ConvexPolyhedronShape {
|
|||
void setRaycastTestType(TriangleRaycastSide testType);
|
||||
|
||||
/// Return the number of faces of the polyhedron
|
||||
virtual uint getNbFaces() const override;
|
||||
virtual uint32 getNbFaces() const override;
|
||||
|
||||
/// Return a given face of the polyhedron
|
||||
virtual const HalfEdgeStructure::Face& getFace(uint faceIndex) const override;
|
||||
virtual const HalfEdgeStructure::Face& getFace(uint32 faceIndex) const override;
|
||||
|
||||
/// Return the number of vertices of the polyhedron
|
||||
virtual uint getNbVertices() const override;
|
||||
virtual uint32 getNbVertices() const override;
|
||||
|
||||
/// Return a given vertex of the polyhedron
|
||||
virtual HalfEdgeStructure::Vertex getVertex(uint vertexIndex) const override;
|
||||
virtual HalfEdgeStructure::Vertex getVertex(uint32 vertexIndex) const override;
|
||||
|
||||
/// Return the position of a given vertex
|
||||
virtual Vector3 getVertexPosition(uint vertexIndex) const override;
|
||||
virtual Vector3 getVertexPosition(uint32 vertexIndex) const override;
|
||||
|
||||
/// Return the normal vector of a given face of the polyhedron
|
||||
virtual Vector3 getFaceNormal(uint faceIndex) const override;
|
||||
virtual Vector3 getFaceNormal(uint32 faceIndex) const override;
|
||||
|
||||
/// Return the number of half-edges of the polyhedron
|
||||
virtual uint getNbHalfEdges() const override;
|
||||
virtual uint32 getNbHalfEdges() const override;
|
||||
|
||||
/// Return a given half-edge of the polyhedron
|
||||
virtual const HalfEdgeStructure::Edge& getHalfEdge(uint edgeIndex) const override;
|
||||
virtual const HalfEdgeStructure::Edge& getHalfEdge(uint32 edgeIndex) const override;
|
||||
|
||||
/// Return the centroid of the polyhedron
|
||||
virtual Vector3 getCentroid() const override;
|
||||
|
@ -234,17 +234,17 @@ RP3D_FORCE_INLINE bool TriangleShape::testPointInside(const Vector3& /*localPoin
|
|||
}
|
||||
|
||||
// Return the number of faces of the polyhedron
|
||||
RP3D_FORCE_INLINE uint TriangleShape::getNbFaces() const {
|
||||
RP3D_FORCE_INLINE uint32 TriangleShape::getNbFaces() const {
|
||||
return 2;
|
||||
}
|
||||
|
||||
// Return the number of vertices of the polyhedron
|
||||
RP3D_FORCE_INLINE uint TriangleShape::getNbVertices() const {
|
||||
RP3D_FORCE_INLINE uint32 TriangleShape::getNbVertices() const {
|
||||
return 3;
|
||||
}
|
||||
|
||||
// Return a given vertex of the polyhedron
|
||||
RP3D_FORCE_INLINE HalfEdgeStructure::Vertex TriangleShape::getVertex(uint vertexIndex) const {
|
||||
RP3D_FORCE_INLINE HalfEdgeStructure::Vertex TriangleShape::getVertex(uint32 vertexIndex) const {
|
||||
assert(vertexIndex < 3);
|
||||
|
||||
HalfEdgeStructure::Vertex vertex(vertexIndex);
|
||||
|
@ -257,13 +257,13 @@ RP3D_FORCE_INLINE HalfEdgeStructure::Vertex TriangleShape::getVertex(uint vertex
|
|||
}
|
||||
|
||||
// Return the position of a given vertex
|
||||
RP3D_FORCE_INLINE Vector3 TriangleShape::getVertexPosition(uint vertexIndex) const {
|
||||
RP3D_FORCE_INLINE Vector3 TriangleShape::getVertexPosition(uint32 vertexIndex) const {
|
||||
assert(vertexIndex < 3);
|
||||
return mPoints[vertexIndex];
|
||||
}
|
||||
|
||||
// Return the normal vector of a given face of the polyhedron
|
||||
RP3D_FORCE_INLINE Vector3 TriangleShape::getFaceNormal(uint faceIndex) const {
|
||||
RP3D_FORCE_INLINE Vector3 TriangleShape::getFaceNormal(uint32 faceIndex) const {
|
||||
assert(faceIndex < 2);
|
||||
assert(mNormal.length() > decimal(0.0));
|
||||
return faceIndex == 0 ? mNormal : -mNormal;
|
||||
|
@ -275,7 +275,7 @@ RP3D_FORCE_INLINE Vector3 TriangleShape::getCentroid() const {
|
|||
}
|
||||
|
||||
// Return the number of half-edges of the polyhedron
|
||||
RP3D_FORCE_INLINE uint TriangleShape::getNbHalfEdges() const {
|
||||
RP3D_FORCE_INLINE uint32 TriangleShape::getNbHalfEdges() const {
|
||||
return 6;
|
||||
}
|
||||
|
||||
|
@ -371,13 +371,13 @@ RP3D_FORCE_INLINE void TriangleShape::computeSmoothTriangleMeshContact(const Col
|
|||
}
|
||||
|
||||
// Return a given face of the polyhedron
|
||||
RP3D_FORCE_INLINE const HalfEdgeStructure::Face& TriangleShape::getFace(uint faceIndex) const {
|
||||
RP3D_FORCE_INLINE const HalfEdgeStructure::Face& TriangleShape::getFace(uint32 faceIndex) const {
|
||||
assert(faceIndex < 2);
|
||||
return mTriangleHalfEdgeStructure.getFace(faceIndex);
|
||||
}
|
||||
|
||||
// Return a given half-edge of the polyhedron
|
||||
RP3D_FORCE_INLINE const HalfEdgeStructure::Edge& TriangleShape::getHalfEdge(uint edgeIndex) const {
|
||||
RP3D_FORCE_INLINE const HalfEdgeStructure::Edge& TriangleShape::getHalfEdge(uint32 edgeIndex) const {
|
||||
assert(edgeIndex < getNbHalfEdges());
|
||||
return mTriangleHalfEdgeStructure.getHalfEdge(edgeIndex);
|
||||
}
|
||||
|
|
|
@ -370,7 +370,7 @@ class RigidBodyComponents : public Components {
|
|||
void removeJointFromBody(Entity bodyEntity, Entity jointEntity);
|
||||
|
||||
/// A an associated contact pairs into the contact pairs array of the body
|
||||
void addContacPair(Entity bodyEntity, uint contactPairIndex);
|
||||
void addContacPair(Entity bodyEntity, uint32 contactPairIndex);
|
||||
|
||||
// -------------------- Friendship -------------------- //
|
||||
|
||||
|
@ -840,7 +840,7 @@ RP3D_FORCE_INLINE void RigidBodyComponents::removeJointFromBody(Entity bodyEntit
|
|||
}
|
||||
|
||||
// A an associated contact pairs into the contact pairs array of the body
|
||||
RP3D_FORCE_INLINE void RigidBodyComponents::addContacPair(Entity bodyEntity, uint contactPairIndex) {
|
||||
RP3D_FORCE_INLINE void RigidBodyComponents::addContacPair(Entity bodyEntity, uint32 contactPairIndex) {
|
||||
|
||||
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||
mContactPairs[mMapEntityToComponentIndex[bodyEntity]].add(contactPairIndex);
|
||||
|
|
|
@ -55,10 +55,10 @@ class Deque {
|
|||
// -------------------- Constants -------------------- //
|
||||
|
||||
/// Number of items in a chunk
|
||||
const uint CHUNK_NB_ITEMS = 17;
|
||||
const uint32 CHUNK_NB_ITEMS = 17;
|
||||
|
||||
/// First item index in a chunk
|
||||
const uint CHUNK_FIRST_ITEM_INDEX = CHUNK_NB_ITEMS / 2;
|
||||
const uint32 CHUNK_FIRST_ITEM_INDEX = CHUNK_NB_ITEMS / 2;
|
||||
|
||||
// -------------------- Attributes -------------------- //
|
||||
|
||||
|
@ -66,16 +66,16 @@ class Deque {
|
|||
T** mChunks;
|
||||
|
||||
/// Number of current elements in the deque
|
||||
size_t mSize;
|
||||
uint32 mSize;
|
||||
|
||||
/// Number of chunks
|
||||
size_t mNbChunks;
|
||||
uint32 mNbChunks;
|
||||
|
||||
/// Index of the chunk with the first element of the deque
|
||||
size_t mFirstChunkIndex;
|
||||
uint32 mFirstChunkIndex;
|
||||
|
||||
/// Index of the chunk with the last element of the deque
|
||||
size_t mLastChunkIndex;
|
||||
uint32 mLastChunkIndex;
|
||||
|
||||
/// Index of the first element in the first chunk
|
||||
uint8 mFirstItemIndex;
|
||||
|
@ -89,15 +89,15 @@ class Deque {
|
|||
// -------------------- Methods -------------------- //
|
||||
|
||||
/// Return a reference to an item at the given virtual index in range [0; mSize-1]
|
||||
T& getItem(size_t virtualIndex) const {
|
||||
T& getItem(uint32 virtualIndex) const {
|
||||
|
||||
// If the virtual index is valid
|
||||
if (virtualIndex < mSize) {
|
||||
|
||||
size_t chunkIndex = mFirstChunkIndex;
|
||||
size_t itemIndex = mFirstItemIndex;
|
||||
uint32 chunkIndex = mFirstChunkIndex;
|
||||
uint32 itemIndex = mFirstItemIndex;
|
||||
|
||||
const size_t nbItemsFirstChunk = CHUNK_NB_ITEMS - mFirstItemIndex;
|
||||
const uint32 nbItemsFirstChunk = CHUNK_NB_ITEMS - mFirstItemIndex;
|
||||
if (virtualIndex < nbItemsFirstChunk) {
|
||||
itemIndex += virtualIndex;
|
||||
}
|
||||
|
@ -118,18 +118,18 @@ class Deque {
|
|||
}
|
||||
|
||||
/// Add more chunks
|
||||
void expandChunks(size_t atLeastNbChunks = 0) {
|
||||
void expandChunks(uint32 atLeastNbChunks = 0) {
|
||||
|
||||
// If it is not necessary to expand the chunks
|
||||
if (atLeastNbChunks > 0 && atLeastNbChunks <= mNbChunks) {
|
||||
return;
|
||||
}
|
||||
|
||||
size_t newNbChunks = mNbChunks == 0 ? 3 : 2 * mNbChunks - 1;
|
||||
uint32 newNbChunks = mNbChunks == 0 ? 3 : 2 * mNbChunks - 1;
|
||||
if (atLeastNbChunks > 0 && newNbChunks < atLeastNbChunks) {
|
||||
newNbChunks = size_t(atLeastNbChunks / 2) * 2 + 1;
|
||||
newNbChunks = uint32(atLeastNbChunks / 2) * 2 + 1;
|
||||
}
|
||||
const size_t halfNbChunksToAdd = mNbChunks == 0 ? 1 : (mNbChunks - 1) / 2;
|
||||
const uint32 halfNbChunksToAdd = mNbChunks == 0 ? 1 : (mNbChunks - 1) / 2;
|
||||
|
||||
// Allocate memory for the new array of pointers to chunk
|
||||
void* newMemory = mAllocator.allocate(newNbChunks * sizeof(T*));
|
||||
|
@ -157,7 +157,7 @@ class Deque {
|
|||
mNbChunks = newNbChunks;
|
||||
|
||||
// Allocate memory for each new chunk
|
||||
for (size_t i=0; i < halfNbChunksToAdd; i++) {
|
||||
for (uint32 i=0; i < halfNbChunksToAdd; i++) {
|
||||
|
||||
// Allocate memory for the new chunk
|
||||
mChunks[i] = static_cast<T*>(mAllocator.allocate(sizeof(T) * CHUNK_NB_ITEMS));
|
||||
|
@ -182,7 +182,7 @@ class Deque {
|
|||
|
||||
private:
|
||||
|
||||
size_t mVirtualIndex;
|
||||
uint32 mVirtualIndex;
|
||||
const Deque<T>* mDeque;
|
||||
|
||||
public:
|
||||
|
@ -200,7 +200,7 @@ class Deque {
|
|||
Iterator() = default;
|
||||
|
||||
/// Constructor
|
||||
Iterator(const Deque<T>* deque, size_t virtualIndex) : mVirtualIndex(virtualIndex), mDeque(deque) {
|
||||
Iterator(const Deque<T>* deque, uint32 virtualIndex) : mVirtualIndex(virtualIndex), mDeque(deque) {
|
||||
|
||||
}
|
||||
|
||||
|
@ -345,14 +345,14 @@ class Deque {
|
|||
|
||||
if (deque.mSize > 0) {
|
||||
|
||||
const size_t dequeHalfSize1 = std::ceil(deque.mSize / 2.0f);
|
||||
const size_t dequeHalfSize2 = deque.mSize - dequeHalfSize1;
|
||||
const uint32 dequeHalfSize1 = std::ceil(deque.mSize / 2.0f);
|
||||
const uint32 dequeHalfSize2 = deque.mSize - dequeHalfSize1;
|
||||
|
||||
// Add the items into the deque
|
||||
for(size_t i=0; i < dequeHalfSize1; i++) {
|
||||
for(uint32 i=0; i < dequeHalfSize1; i++) {
|
||||
addFront(deque[dequeHalfSize1 - 1 - i]);
|
||||
}
|
||||
for(size_t i=0; i < dequeHalfSize2; i++) {
|
||||
for(uint32 i=0; i < dequeHalfSize2; i++) {
|
||||
addBack(deque[dequeHalfSize1 + i]);
|
||||
}
|
||||
}
|
||||
|
@ -364,7 +364,7 @@ class Deque {
|
|||
clear();
|
||||
|
||||
// Release each chunk
|
||||
for (size_t i=0; i < mNbChunks; i++) {
|
||||
for (uint32 i=0; i < mNbChunks; i++) {
|
||||
|
||||
mAllocator.release(mChunks[i], sizeof(T) * CHUNK_NB_ITEMS);
|
||||
}
|
||||
|
@ -519,7 +519,7 @@ class Deque {
|
|||
if (mSize > 0) {
|
||||
|
||||
// Call the destructor of every items
|
||||
for (size_t i=0; i < mSize; i++) {
|
||||
for (uint32 i=0; i < mSize; i++) {
|
||||
getItem(i).~T();
|
||||
}
|
||||
|
||||
|
@ -533,18 +533,18 @@ class Deque {
|
|||
}
|
||||
|
||||
/// Return the number of elements in the deque
|
||||
size_t size() const {
|
||||
uint32 size() const {
|
||||
return mSize;
|
||||
}
|
||||
|
||||
/// Overloaded index operator
|
||||
T& operator[](const uint index) {
|
||||
T& operator[](const uint32 index) {
|
||||
assert(index < mSize);
|
||||
return getItem(index);
|
||||
}
|
||||
|
||||
/// Overloaded const index operator
|
||||
const T& operator[](const uint index) const {
|
||||
const T& operator[](const uint32 index) const {
|
||||
assert(index < mSize);
|
||||
return getItem(index);
|
||||
}
|
||||
|
@ -554,7 +554,7 @@ class Deque {
|
|||
|
||||
if (mSize != deque.mSize) return false;
|
||||
|
||||
for (size_t i=0; i < mSize; i++) {
|
||||
for (uint32 i=0; i < mSize; i++) {
|
||||
if (getItem(i) != deque.getItem(i)) {
|
||||
return false;
|
||||
}
|
||||
|
@ -580,19 +580,19 @@ class Deque {
|
|||
if (deque.mSize > 0) {
|
||||
|
||||
// Number of used chunks
|
||||
const size_t nbUsedChunks = deque.mLastChunkIndex - deque.mFirstChunkIndex + 1;
|
||||
const uint32 nbUsedChunks = deque.mLastChunkIndex - deque.mFirstChunkIndex + 1;
|
||||
|
||||
// Expand the chunk if necessary
|
||||
expandChunks(nbUsedChunks);
|
||||
|
||||
const size_t dequeHalfSize1 = std::ceil(deque.mSize / 2.0f);
|
||||
const size_t dequeHalfSize2 = deque.mSize - dequeHalfSize1;
|
||||
const uint32 dequeHalfSize1 = std::ceil(deque.mSize / 2.0f);
|
||||
const uint32 dequeHalfSize2 = deque.mSize - dequeHalfSize1;
|
||||
|
||||
// Add the items into the deque
|
||||
for(size_t i=0; i < dequeHalfSize1; i++) {
|
||||
for(uint32 i=0; i < dequeHalfSize1; i++) {
|
||||
addFront(deque[dequeHalfSize1 - 1 - i]);
|
||||
}
|
||||
for(size_t i=0; i < dequeHalfSize2; i++) {
|
||||
for(uint32 i=0; i < dequeHalfSize2; i++) {
|
||||
addBack(deque[dequeHalfSize1 + i]);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -51,15 +51,15 @@ class Stack {
|
|||
T* mArray;
|
||||
|
||||
/// Number of elements in the stack
|
||||
uint mNbElements;
|
||||
uint32 mNbElements;
|
||||
|
||||
/// Number of allocated elements in the stack
|
||||
uint mCapacity;
|
||||
uint32 mCapacity;
|
||||
|
||||
// -------------------- Methods -------------------- //
|
||||
|
||||
/// Allocate more memory
|
||||
void allocate(size_t capacity) {
|
||||
void allocate(uint32 capacity) {
|
||||
|
||||
T* newArray = static_cast<T*>(mAllocator.allocate(capacity * sizeof(T)));
|
||||
assert(newArray != nullptr);
|
||||
|
@ -87,7 +87,7 @@ class Stack {
|
|||
// -------------------- Methods -------------------- //
|
||||
|
||||
/// Constructor
|
||||
Stack(MemoryAllocator& allocator, size_t capacity = 0)
|
||||
Stack(MemoryAllocator& allocator, uint32 capacity = 0)
|
||||
:mAllocator(allocator), mArray(nullptr), mNbElements(0), mCapacity(0) {
|
||||
|
||||
if (capacity > 0) {
|
||||
|
@ -130,7 +130,7 @@ class Stack {
|
|||
void clear() {
|
||||
|
||||
// Destruct the items
|
||||
for (size_t i = 0; i < mNbElements; i++) {
|
||||
for (uint32 i = 0; i < mNbElements; i++) {
|
||||
mArray[i].~T();
|
||||
}
|
||||
|
||||
|
@ -169,12 +169,12 @@ class Stack {
|
|||
}
|
||||
|
||||
/// Return the number of items in the stack
|
||||
size_t size() const {
|
||||
uint32 size() const {
|
||||
return mNbElements;
|
||||
}
|
||||
|
||||
/// Return the capacity of the stack
|
||||
size_t capacity() const {
|
||||
uint32 capacity() const {
|
||||
return mCapacity;
|
||||
}
|
||||
};
|
||||
|
|
|
@ -85,13 +85,13 @@ class Island {
|
|||
void addJoint(Joint* joint);
|
||||
|
||||
/// Return the number of bodies in the island
|
||||
uint getNbBodies() const;
|
||||
uint32 getNbBodies() const;
|
||||
|
||||
/// Return the number of contact manifolds in the island
|
||||
uint getNbContactManifolds() const;
|
||||
uint32 getNbContactManifolds() const;
|
||||
|
||||
/// Return the number of joints in the island
|
||||
uint getNbJoints() const;
|
||||
uint32 getNbJoints() const;
|
||||
|
||||
/// Return a pointer to the array of bodies
|
||||
RigidBody** getBodies();
|
||||
|
@ -118,12 +118,12 @@ RP3D_FORCE_INLINE void Island::addContactManifold(ContactManifold* contactManifo
|
|||
}
|
||||
|
||||
// Return the number of bodies in the island
|
||||
RP3D_FORCE_INLINE uint Island::getNbBodies() const {
|
||||
RP3D_FORCE_INLINE uint32 Island::getNbBodies() const {
|
||||
return mNbBodies;
|
||||
}
|
||||
|
||||
// Return the number of contact manifolds in the island
|
||||
RP3D_FORCE_INLINE uint Island::getNbContactManifolds() const {
|
||||
RP3D_FORCE_INLINE uint32 Island::getNbContactManifolds() const {
|
||||
return mNbContactManifolds;
|
||||
}
|
||||
|
||||
|
|
|
@ -270,9 +270,6 @@ class PhysicsWorld {
|
|||
/// becomes smaller than the sleep velocity.
|
||||
decimal mTimeBeforeSleep;
|
||||
|
||||
/// Current joint id
|
||||
uint mCurrentJointId;
|
||||
|
||||
// -------------------- Methods -------------------- //
|
||||
|
||||
/// Constructor
|
||||
|
@ -370,7 +367,7 @@ class PhysicsWorld {
|
|||
uint getNbIterationsPositionSolver() const;
|
||||
|
||||
/// Set the number of iterations for the position constraint solver
|
||||
void setNbIterationsPositionSolver(uint nbIterations);
|
||||
void setNbIterationsPositionSolver(uint32 nbIterations);
|
||||
|
||||
/// Set the position correction technique used for contacts
|
||||
void setContactsPositionCorrectionTechnique(ContactsPositionCorrectionTechnique technique);
|
||||
|
@ -433,19 +430,19 @@ class PhysicsWorld {
|
|||
uint getNbCollisionBodies() const;
|
||||
|
||||
/// Return a constant pointer to a given CollisionBody of the world
|
||||
const CollisionBody* getCollisionBody(uint index) const;
|
||||
const CollisionBody* getCollisionBody(uint32 index) const;
|
||||
|
||||
/// Return a pointer to a given CollisionBody of the world
|
||||
CollisionBody* getCollisionBody(uint index) ;
|
||||
CollisionBody* getCollisionBody(uint32 index) ;
|
||||
|
||||
/// Return the number of RigidBody in the physics world
|
||||
uint getNbRigidBodies() const;
|
||||
|
||||
/// Return a constant pointer to a given RigidBody of the world
|
||||
const RigidBody* getRigidBody(uint index) const;
|
||||
const RigidBody* getRigidBody(uint32 index) const;
|
||||
|
||||
/// Return a pointer to a given RigidBody of the world
|
||||
RigidBody* getRigidBody(uint index) ;
|
||||
RigidBody* getRigidBody(uint32 index) ;
|
||||
|
||||
/// Return true if the debug rendering is enabled
|
||||
bool getIsDebugRenderingEnabled() const;
|
||||
|
|
|
@ -307,10 +307,10 @@ class ContactSolverSystem {
|
|||
ContactPointSolver* mContactPoints;
|
||||
|
||||
/// Number of contact point constraints
|
||||
uint mNbContactPoints;
|
||||
uint32 mNbContactPoints;
|
||||
|
||||
/// Number of contact constraints
|
||||
uint mNbContactManifolds;
|
||||
uint32 mNbContactManifolds;
|
||||
|
||||
/// Reference to the islands
|
||||
Islands& mIslands;
|
||||
|
@ -372,7 +372,7 @@ class ContactSolverSystem {
|
|||
void init(Array<ContactManifold>* contactManifolds, Array<ContactPoint>* contactPoints, decimal timeStep);
|
||||
|
||||
/// Initialize the constraint solver for a given island
|
||||
void initializeForIsland(uint islandIndex);
|
||||
void initializeForIsland(uint32 islandIndex);
|
||||
|
||||
/// Store the computed impulses to use them to
|
||||
/// warm start the solver at the next iteration
|
||||
|
|
|
@ -140,7 +140,7 @@ uint32 CollisionBody::getNbColliders() const {
|
|||
* @param index Index of a Collider of the body
|
||||
* @return The const pointer of a given collider of the body
|
||||
*/
|
||||
const Collider* CollisionBody::getCollider(uint colliderIndex) const {
|
||||
const Collider* CollisionBody::getCollider(uint32 colliderIndex) const {
|
||||
|
||||
assert(colliderIndex < getNbColliders());
|
||||
|
||||
|
@ -154,7 +154,7 @@ const Collider* CollisionBody::getCollider(uint colliderIndex) const {
|
|||
* @param index Index of a Collider of the body
|
||||
* @return The pointer of a given collider of the body
|
||||
*/
|
||||
Collider* CollisionBody::getCollider(uint colliderIndex) {
|
||||
Collider* CollisionBody::getCollider(uint32 colliderIndex) {
|
||||
|
||||
assert(colliderIndex < getNbColliders());
|
||||
|
||||
|
|
|
@ -198,7 +198,7 @@ void TriangleVertexArray::computeVerticesNormals() {
|
|||
* @param triangleIndex Index of a given triangle in the array
|
||||
* @param[out] outVerticesIndices Pointer to the three output vertex indices
|
||||
*/
|
||||
void TriangleVertexArray::getTriangleVerticesIndices(uint32 triangleIndex, uint32 *outVerticesIndices) const {
|
||||
void TriangleVertexArray::getTriangleVerticesIndices(uint32 triangleIndex, uint32* outVerticesIndices) const {
|
||||
|
||||
assert(triangleIndex < mNbTriangles);
|
||||
|
||||
|
|
|
@ -55,13 +55,13 @@ SATAlgorithm::SATAlgorithm(bool clipWithPreviousAxisIfStillColliding, MemoryAllo
|
|||
}
|
||||
|
||||
// Test collision between a sphere and a convex mesh
|
||||
bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex, uint batchNbItems) const {
|
||||
bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint32 batchStartIndex, uint32 batchNbItems) const {
|
||||
|
||||
bool isCollisionFound = false;
|
||||
|
||||
RP3D_PROFILE("SATAlgorithm::testCollisionSphereVsConvexPolyhedron()", mProfiler);
|
||||
|
||||
for (uint batchIndex = batchStartIndex; batchIndex < batchStartIndex + batchNbItems; batchIndex++) {
|
||||
for (uint32 batchIndex = batchStartIndex; batchIndex < batchStartIndex + batchNbItems; batchIndex++) {
|
||||
|
||||
bool isSphereShape1 = narrowPhaseInfoBatch.narrowPhaseInfos[batchIndex].collisionShape1->getType() == CollisionShapeType::SPHERE;
|
||||
|
||||
|
@ -86,11 +86,11 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfoBatch& n
|
|||
|
||||
// Minimum penetration depth
|
||||
decimal minPenetrationDepth = DECIMAL_LARGEST;
|
||||
uint minFaceIndex = 0;
|
||||
uint32 minFaceIndex = 0;
|
||||
bool noContact = false;
|
||||
|
||||
// For each face of the convex mesh
|
||||
for (uint f = 0; f < polyhedron->getNbFaces(); f++) {
|
||||
for (uint32 f = 0; f < polyhedron->getNbFaces(); f++) {
|
||||
|
||||
// Compute the penetration depth of the shapes along the face normal direction
|
||||
decimal penetrationDepth = computePolyhedronFaceVsSpherePenetrationDepth(f, polyhedron, sphere, sphereCenter);
|
||||
|
@ -144,7 +144,7 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfoBatch& n
|
|||
}
|
||||
|
||||
// Compute the penetration depth between a face of the polyhedron and a sphere along the polyhedron face normal direction
|
||||
decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint faceIndex, const ConvexPolyhedronShape* polyhedron,
|
||||
decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint32 faceIndex, const ConvexPolyhedronShape* polyhedron,
|
||||
const SphereShape* sphere, const Vector3& sphereCenter) const {
|
||||
|
||||
RP3D_PROFILE("SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth)", mProfiler);
|
||||
|
@ -162,7 +162,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint faceInd
|
|||
}
|
||||
|
||||
// Test collision between a capsule and a convex mesh
|
||||
bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchIndex) const {
|
||||
bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint32 batchIndex) const {
|
||||
|
||||
RP3D_PROFILE("SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron()", mProfiler);
|
||||
|
||||
|
@ -189,14 +189,14 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfoBatch&
|
|||
|
||||
// Minimum penetration depth
|
||||
decimal minPenetrationDepth = DECIMAL_LARGEST;
|
||||
uint minFaceIndex = 0;
|
||||
uint32 minFaceIndex = 0;
|
||||
bool isMinPenetrationFaceNormal = false;
|
||||
Vector3 separatingAxisCapsuleSpace;
|
||||
Vector3 separatingPolyhedronEdgeVertex1;
|
||||
Vector3 separatingPolyhedronEdgeVertex2;
|
||||
|
||||
// For each face of the convex mesh
|
||||
for (uint f = 0; f < polyhedron->getNbFaces(); f++) {
|
||||
for (uint32 f = 0; f < polyhedron->getNbFaces(); f++) {
|
||||
|
||||
Vector3 outFaceNormalCapsuleSpace;
|
||||
|
||||
|
@ -221,7 +221,7 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfoBatch&
|
|||
}
|
||||
|
||||
// For each direction that is the cross product of the capsule inner segment and an edge of the polyhedron
|
||||
for (uint e = 0; e < polyhedron->getNbHalfEdges(); e += 2) {
|
||||
for (uint32 e = 0; e < polyhedron->getNbHalfEdges(); e += 2) {
|
||||
|
||||
// Get an edge from the polyhedron (convert it into the capsule local-space)
|
||||
const HalfEdgeStructure::Edge& edge = polyhedron->getHalfEdge(e);
|
||||
|
@ -354,7 +354,7 @@ decimal SATAlgorithm::computeEdgeVsCapsuleInnerSegmentPenetrationDepth(const Con
|
|||
}
|
||||
|
||||
// Compute the penetration depth between the face of a polyhedron and a capsule along the polyhedron face normal direction
|
||||
decimal SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth(uint polyhedronFaceIndex, const ConvexPolyhedronShape* polyhedron,
|
||||
decimal SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth(uint32 polyhedronFaceIndex, const ConvexPolyhedronShape* polyhedron,
|
||||
const CapsuleShape* capsule, const Transform& polyhedronToCapsuleTransform,
|
||||
Vector3& outFaceNormalCapsuleSpace) const {
|
||||
|
||||
|
@ -378,11 +378,11 @@ decimal SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth(uint polyhe
|
|||
|
||||
// Compute the two contact points between a polyhedron and a capsule when the separating
|
||||
// axis is a face normal of the polyhedron
|
||||
bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron,
|
||||
bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint32 referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron,
|
||||
decimal penetrationDepth, const Transform& polyhedronToCapsuleTransform,
|
||||
Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace,
|
||||
const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace,
|
||||
NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchIndex, bool isCapsuleShape1) const {
|
||||
NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint32 batchIndex, bool isCapsuleShape1) const {
|
||||
|
||||
RP3D_PROFILE("SATAlgorithm::computeCapsulePolyhedronFaceContactPoints", mProfiler);
|
||||
|
||||
|
@ -391,8 +391,8 @@ bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI
|
|||
// Get the face normal
|
||||
Vector3 faceNormal = polyhedron->getFaceNormal(referenceFaceIndex);
|
||||
|
||||
uint firstEdgeIndex = face.edgeIndex;
|
||||
uint edgeIndex = firstEdgeIndex;
|
||||
uint32 firstEdgeIndex = face.edgeIndex;
|
||||
uint32 edgeIndex = firstEdgeIndex;
|
||||
|
||||
Array<Vector3> planesPoints(mMemoryAllocator, 2);
|
||||
Array<Vector3> planesNormals(mMemoryAllocator, 2);
|
||||
|
@ -478,13 +478,13 @@ bool SATAlgorithm::isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, c
|
|||
}
|
||||
|
||||
// Test collision between two convex polyhedrons
|
||||
bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex, uint batchNbItems) const {
|
||||
bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint32 batchStartIndex, uint32 batchNbItems) const {
|
||||
|
||||
RP3D_PROFILE("SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron()", mProfiler);
|
||||
|
||||
bool isCollisionFound = false;
|
||||
|
||||
for (uint batchIndex = batchStartIndex; batchIndex < batchStartIndex + batchNbItems; batchIndex++) {
|
||||
for (uint32 batchIndex = batchStartIndex; batchIndex < batchStartIndex + batchNbItems; batchIndex++) {
|
||||
|
||||
assert(narrowPhaseInfoBatch.narrowPhaseInfos[batchIndex].collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON);
|
||||
assert(narrowPhaseInfoBatch.narrowPhaseInfos[batchIndex].collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON);
|
||||
|
@ -497,11 +497,11 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn
|
|||
const Transform polyhedron2ToPolyhedron1 = polyhedron1ToPolyhedron2.getInverse();
|
||||
|
||||
decimal minPenetrationDepth = DECIMAL_LARGEST;
|
||||
uint minFaceIndex = 0;
|
||||
uint32 minFaceIndex = 0;
|
||||
bool isMinPenetrationFaceNormal = false;
|
||||
bool isMinPenetrationFaceNormalPolyhedron1 = false;
|
||||
uint minSeparatingEdge1Index = 0;
|
||||
uint minSeparatingEdge2Index = 0;
|
||||
uint32 minSeparatingEdge1Index = 0;
|
||||
uint32 minSeparatingEdge2Index = 0;
|
||||
Vector3 separatingEdge1A, separatingEdge1B;
|
||||
Vector3 separatingEdge2A, separatingEdge2B;
|
||||
Vector3 minEdgeVsEdgeSeparatingAxisPolyhedron2Space;
|
||||
|
@ -688,7 +688,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn
|
|||
isMinPenetrationFaceNormal = false;
|
||||
|
||||
// Test all the face normals of the polyhedron 1 for separating axis
|
||||
uint faceIndex1;
|
||||
uint32 faceIndex1;
|
||||
decimal penetrationDepth1 = testFacesDirectionPolyhedronVsPolyhedron(polyhedron1, polyhedron2, polyhedron1ToPolyhedron2, faceIndex1);
|
||||
if (penetrationDepth1 <= decimal(0.0)) {
|
||||
|
||||
|
@ -701,7 +701,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn
|
|||
}
|
||||
|
||||
// Test all the face normals of the polyhedron 2 for separating axis
|
||||
uint faceIndex2;
|
||||
uint32 faceIndex2;
|
||||
decimal penetrationDepth2 = testFacesDirectionPolyhedronVsPolyhedron(polyhedron2, polyhedron1, polyhedron2ToPolyhedron1, faceIndex2);
|
||||
if (penetrationDepth2 <= decimal(0.0)) {
|
||||
|
||||
|
@ -742,7 +742,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn
|
|||
bool separatingAxisFound = false;
|
||||
|
||||
// Test the cross products of edges of polyhedron 1 with edges of polyhedron 2 for separating axis
|
||||
for (uint i=0; i < polyhedron1->getNbHalfEdges(); i += 2) {
|
||||
for (uint32 i=0; i < polyhedron1->getNbHalfEdges(); i += 2) {
|
||||
|
||||
// Get an edge of polyhedron 1
|
||||
const HalfEdgeStructure::Edge& edge1 = polyhedron1->getHalfEdge(i);
|
||||
|
@ -751,7 +751,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn
|
|||
const Vector3 edge1B = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(polyhedron1->getHalfEdge(edge1.nextEdgeIndex).vertexIndex);
|
||||
const Vector3 edge1Direction = edge1B - edge1A;
|
||||
|
||||
for (uint j=0; j < polyhedron2->getNbHalfEdges(); j += 2) {
|
||||
for (uint32 j=0; j < polyhedron2->getNbHalfEdges(); j += 2) {
|
||||
|
||||
// Get an edge of polyhedron 2
|
||||
const HalfEdgeStructure::Edge& edge2 = polyhedron2->getHalfEdge(j);
|
||||
|
@ -890,7 +890,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn
|
|||
bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPenetrationFaceNormalPolyhedron1,
|
||||
const ConvexPolyhedronShape* polyhedron1, const ConvexPolyhedronShape* polyhedron2,
|
||||
const Transform& polyhedron1ToPolyhedron2, const Transform& polyhedron2ToPolyhedron1,
|
||||
uint minFaceIndex, NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchIndex) const {
|
||||
uint32 minFaceIndex, NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint32 batchIndex) const {
|
||||
|
||||
RP3D_PROFILE("SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints", mProfiler);
|
||||
|
||||
|
@ -919,7 +919,7 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene
|
|||
const HalfEdgeStructure::Face& referenceFace = referencePolyhedron->getFace(minFaceIndex);
|
||||
|
||||
// Find the incident face on the other polyhedron (most anti-parallel face)
|
||||
uint incidentFaceIndex = incidentPolyhedron->findMostAntiParallelFace(axisIncidentSpace);
|
||||
uint32 incidentFaceIndex = incidentPolyhedron->findMostAntiParallelFace(axisIncidentSpace);
|
||||
|
||||
// Get the incident face
|
||||
const HalfEdgeStructure::Face& incidentFace = incidentPolyhedron->getFace(incidentFaceIndex);
|
||||
|
@ -939,7 +939,7 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene
|
|||
uint32 firstEdgeIndex = referenceFace.edgeIndex;
|
||||
bool areVertices1Input = false;
|
||||
uint32 nbOutputVertices;
|
||||
uint currentEdgeIndex;
|
||||
uint32 currentEdgeIndex;
|
||||
|
||||
// Get the adjacent edge
|
||||
const HalfEdgeStructure::Edge* currentEdge = &(referencePolyhedron->getHalfEdge(firstEdgeIndex));
|
||||
|
@ -1084,7 +1084,7 @@ decimal SATAlgorithm::computeDistanceBetweenEdges(const Vector3& edge1A, const V
|
|||
decimal SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1,
|
||||
const ConvexPolyhedronShape* polyhedron2,
|
||||
const Transform& polyhedron1ToPolyhedron2,
|
||||
uint faceIndex) const {
|
||||
uint32 faceIndex) const {
|
||||
|
||||
RP3D_PROFILE("SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron", mProfiler);
|
||||
|
||||
|
@ -1117,7 +1117,7 @@ decimal SATAlgorithm::testFacesDirectionPolyhedronVsPolyhedron(const ConvexPolyh
|
|||
decimal minPenetrationDepth = DECIMAL_LARGEST;
|
||||
|
||||
// For each face of the first polyhedron
|
||||
for (uint f = 0; f < polyhedron1->getNbFaces(); f++) {
|
||||
for (uint32 f = 0; f < polyhedron1->getNbFaces(); f++) {
|
||||
|
||||
decimal penetrationDepth = testSingleFaceDirectionPolyhedronVsPolyhedron(polyhedron1, polyhedron2,
|
||||
polyhedron1ToPolyhedron2, f);
|
||||
|
|
|
@ -50,13 +50,13 @@ void ConcaveMeshShape::initBVHTree() {
|
|||
// TODO : Try to randomly add the triangles into the tree to obtain a better tree
|
||||
|
||||
// For each sub-part of the mesh
|
||||
for (uint subPart=0; subPart<mTriangleMesh->getNbSubparts(); subPart++) {
|
||||
for (uint32 subPart=0; subPart<mTriangleMesh->getNbSubparts(); subPart++) {
|
||||
|
||||
// Get the triangle vertex array of the current sub-part
|
||||
TriangleVertexArray* triangleVertexArray = mTriangleMesh->getSubpart(subPart);
|
||||
|
||||
// For each triangle of the concave mesh
|
||||
for (uint triangleIndex=0; triangleIndex<triangleVertexArray->getNbTriangles(); triangleIndex++) {
|
||||
for (uint32 triangleIndex=0; triangleIndex<triangleVertexArray->getNbTriangles(); triangleIndex++) {
|
||||
|
||||
Vector3 trianglePoints[3];
|
||||
|
||||
|
@ -73,7 +73,7 @@ void ConcaveMeshShape::initBVHTree() {
|
|||
}
|
||||
|
||||
// Return the three vertices coordinates (in the array outTriangleVertices) of a triangle
|
||||
void ConcaveMeshShape::getTriangleVertices(uint subPart, uint triangleIndex, Vector3* outTriangleVertices) const {
|
||||
void ConcaveMeshShape::getTriangleVertices(uint32 subPart, uint32 triangleIndex, Vector3* outTriangleVertices) const {
|
||||
|
||||
// Get the triangle vertex array of the current sub-part
|
||||
TriangleVertexArray* triangleVertexArray = mTriangleMesh->getSubpart(subPart);
|
||||
|
@ -94,7 +94,7 @@ void ConcaveMeshShape::getTriangleVertices(uint subPart, uint triangleIndex, Vec
|
|||
}
|
||||
|
||||
// Return the three vertex normals (in the array outVerticesNormals) of a triangle
|
||||
void ConcaveMeshShape::getTriangleVerticesNormals(uint subPart, uint triangleIndex, Vector3* outVerticesNormals) const {
|
||||
void ConcaveMeshShape::getTriangleVerticesNormals(uint32 subPart, uint32 triangleIndex, Vector3* outVerticesNormals) const {
|
||||
|
||||
// Get the triangle vertex array of the current sub-part
|
||||
TriangleVertexArray* triangleVertexArray = mTriangleMesh->getSubpart(subPart);
|
||||
|
@ -104,7 +104,7 @@ void ConcaveMeshShape::getTriangleVerticesNormals(uint subPart, uint triangleInd
|
|||
}
|
||||
|
||||
// Return the indices of the three vertices of a given triangle in the array
|
||||
void ConcaveMeshShape::getTriangleVerticesIndices(uint subPart, uint triangleIndex, uint* outVerticesIndices) const {
|
||||
void ConcaveMeshShape::getTriangleVerticesIndices(uint32 subPart, uint32 triangleIndex, uint32* outVerticesIndices) const {
|
||||
|
||||
// Get the triangle vertex array of the current sub-part
|
||||
TriangleVertexArray* triangleVertexArray = mTriangleMesh->getSubpart(subPart);
|
||||
|
@ -114,13 +114,13 @@ void ConcaveMeshShape::getTriangleVerticesIndices(uint subPart, uint triangleInd
|
|||
}
|
||||
|
||||
// Return the number of sub parts contained in this mesh
|
||||
uint ConcaveMeshShape::getNbSubparts() const
|
||||
uint32 ConcaveMeshShape::getNbSubparts() const
|
||||
{
|
||||
return mTriangleMesh->getNbSubparts();
|
||||
}
|
||||
|
||||
// Return the number of triangles in a sub part of the mesh
|
||||
uint ConcaveMeshShape::getNbTriangles(uint subPart) const
|
||||
uint32 ConcaveMeshShape::getNbTriangles(uint32 subPart) const
|
||||
{
|
||||
assert(mTriangleMesh->getSubpart(subPart));
|
||||
return mTriangleMesh->getSubpart(subPart)->getNbTriangles();
|
||||
|
@ -128,7 +128,7 @@ uint ConcaveMeshShape::getNbTriangles(uint subPart) const
|
|||
|
||||
// Compute all the triangles of the mesh that are overlapping with the AABB in parameter
|
||||
void ConcaveMeshShape::computeOverlappingTriangles(const AABB& localAABB, Array<Vector3>& triangleVertices,
|
||||
Array<Vector3>& triangleVerticesNormals, Array<uint>& shapeIds,
|
||||
Array<Vector3>& triangleVerticesNormals, Array<uint32>& shapeIds,
|
||||
MemoryAllocator& allocator) const {
|
||||
|
||||
RP3D_PROFILE("ConcaveMeshShape::computeOverlappingTriangles()", mProfiler);
|
||||
|
@ -149,7 +149,7 @@ void ConcaveMeshShape::computeOverlappingTriangles(const AABB& localAABB, Array<
|
|||
triangleVerticesNormals.addWithoutInit(nbOverlappingNodes * 3);
|
||||
|
||||
// For each overlapping node
|
||||
for (uint i=0; i < nbOverlappingNodes; i++) {
|
||||
for (uint32 i=0; i < nbOverlappingNodes; i++) {
|
||||
|
||||
int nodeId = overlappingNodes[i];
|
||||
|
||||
|
@ -201,13 +201,13 @@ bool ConcaveMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collide
|
|||
}
|
||||
|
||||
// Compute the shape Id for a given triangle of the mesh
|
||||
uint ConcaveMeshShape::computeTriangleShapeId(uint subPart, uint triangleIndex) const {
|
||||
uint32 ConcaveMeshShape::computeTriangleShapeId(uint32 subPart, uint32 triangleIndex) const {
|
||||
|
||||
RP3D_PROFILE("ConcaveMeshShape::computeTriangleShapeId()", mProfiler);
|
||||
|
||||
uint shapeId = 0;
|
||||
uint32 shapeId = 0;
|
||||
|
||||
uint i=0;
|
||||
uint32 i=0;
|
||||
while (i < subPart) {
|
||||
|
||||
shapeId += mTriangleMesh->getSubpart(i)->getNbTriangles();
|
||||
|
@ -290,7 +290,7 @@ std::string ConcaveMeshShape::to_string() const {
|
|||
ss << "nbSubparts=" << mTriangleMesh->getNbSubparts() << std::endl;
|
||||
|
||||
// Vertices array
|
||||
for (uint subPart=0; subPart<mTriangleMesh->getNbSubparts(); subPart++) {
|
||||
for (uint32 subPart=0; subPart<mTriangleMesh->getNbSubparts(); subPart++) {
|
||||
|
||||
// Get the triangle vertex array of the current sub-part
|
||||
TriangleVertexArray* triangleVertexArray = mTriangleMesh->getSubpart(subPart);
|
||||
|
@ -302,7 +302,7 @@ std::string ConcaveMeshShape::to_string() const {
|
|||
ss << "vertices=[";
|
||||
|
||||
// For each triangle of the concave mesh
|
||||
for (uint v=0; v<triangleVertexArray->getNbVertices(); v++) {
|
||||
for (uint32 v=0; v<triangleVertexArray->getNbVertices(); v++) {
|
||||
|
||||
Vector3 vertex;
|
||||
triangleVertexArray->getVertex(v, &vertex);
|
||||
|
@ -315,7 +315,7 @@ std::string ConcaveMeshShape::to_string() const {
|
|||
ss << "normals=[";
|
||||
|
||||
// For each triangle of the concave mesh
|
||||
for (uint v=0; v<triangleVertexArray->getNbVertices(); v++) {
|
||||
for (uint32 v=0; v<triangleVertexArray->getNbVertices(); v++) {
|
||||
|
||||
Vector3 normal;
|
||||
triangleVertexArray->getNormal(v, &normal);
|
||||
|
@ -329,9 +329,9 @@ std::string ConcaveMeshShape::to_string() const {
|
|||
|
||||
// For each triangle of the concave mesh
|
||||
// For each triangle of the concave mesh
|
||||
for (uint triangleIndex=0; triangleIndex<triangleVertexArray->getNbTriangles(); triangleIndex++) {
|
||||
for (uint32 triangleIndex=0; triangleIndex<triangleVertexArray->getNbTriangles(); triangleIndex++) {
|
||||
|
||||
uint indices[3];
|
||||
uint32 indices[3];
|
||||
|
||||
triangleVertexArray->getTriangleVerticesIndices(triangleIndex, indices);
|
||||
|
||||
|
|
|
@ -94,7 +94,7 @@ void HeightFieldShape::getLocalBounds(Vector3& min, Vector3& max) const {
|
|||
// to test for collision. We compute the sub-grid points that are inside the other body's AABB
|
||||
// and then for each rectangle in the sub-grid we generate two triangles that we use to test collision.
|
||||
void HeightFieldShape::computeOverlappingTriangles(const AABB& localAABB, Array<Vector3>& triangleVertices,
|
||||
Array<Vector3>& triangleVerticesNormals, Array<uint>& shapeIds,
|
||||
Array<Vector3>& triangleVerticesNormals, Array<uint32>& shapeIds,
|
||||
MemoryAllocator& /*allocator*/) const {
|
||||
|
||||
RP3D_PROFILE("HeightFieldShape::computeOverlappingTriangles()", mProfiler);
|
||||
|
@ -299,7 +299,7 @@ bool HeightFieldShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collide
|
|||
const Vector3 p4 = getVertexAt(i + 1, j + 1);
|
||||
|
||||
// Raycast against the first triangle of the cell
|
||||
uint shapeId = computeTriangleShapeId(i, j, 0);
|
||||
uint32 shapeId = computeTriangleShapeId(i, j, 0);
|
||||
isHit |= raycastTriangle(ray, p1, p2, p3, shapeId, collider, raycastInfo, smallestHitFraction, allocator);
|
||||
|
||||
// Raycast against the second triangle of the cell
|
||||
|
@ -323,7 +323,7 @@ bool HeightFieldShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collide
|
|||
}
|
||||
|
||||
// Raycast a single triangle of the height-field
|
||||
bool HeightFieldShape::raycastTriangle(const Ray& ray, const Vector3& p1, const Vector3& p2, const Vector3& p3, uint shapeId,
|
||||
bool HeightFieldShape::raycastTriangle(const Ray& ray, const Vector3& p1, const Vector3& p2, const Vector3& p3, uint32 shapeId,
|
||||
Collider* collider, RaycastInfo& raycastInfo, decimal& smallestHitFraction, MemoryAllocator& allocator) const {
|
||||
|
||||
// Generate the first triangle for the current grid rectangle
|
||||
|
|
|
@ -37,7 +37,7 @@ using namespace reactphysics3d;
|
|||
|
||||
|
||||
// Constructor
|
||||
TriangleShape::TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint shapeId, HalfEdgeStructure& triangleHalfEdgeStructure, MemoryAllocator& allocator)
|
||||
TriangleShape::TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint32 shapeId, HalfEdgeStructure& triangleHalfEdgeStructure, MemoryAllocator& allocator)
|
||||
: ConvexPolyhedronShape(CollisionShapeName::TRIANGLE, allocator), mTriangleHalfEdgeStructure(triangleHalfEdgeStructure) {
|
||||
|
||||
mPoints[0] = vertices[0];
|
||||
|
@ -58,7 +58,7 @@ TriangleShape::TriangleShape(const Vector3* vertices, const Vector3* verticesNor
|
|||
}
|
||||
|
||||
// Constructor for raycasting
|
||||
TriangleShape::TriangleShape(const Vector3* vertices, uint shapeId, HalfEdgeStructure& triangleHalfEdgeStructure, MemoryAllocator& allocator)
|
||||
TriangleShape::TriangleShape(const Vector3* vertices, uint32 shapeId, HalfEdgeStructure& triangleHalfEdgeStructure, MemoryAllocator& allocator)
|
||||
: ConvexPolyhedronShape(CollisionShapeName::TRIANGLE, allocator), mTriangleHalfEdgeStructure(triangleHalfEdgeStructure) {
|
||||
|
||||
mPoints[0] = vertices[0];
|
||||
|
|
|
@ -42,7 +42,7 @@ using namespace std;
|
|||
|
||||
// Static initializations
|
||||
|
||||
uint PhysicsWorld::mNbWorlds = 0;
|
||||
uint32 PhysicsWorld::mNbWorlds = 0;
|
||||
|
||||
// Constructor
|
||||
/**
|
||||
|
@ -75,7 +75,7 @@ PhysicsWorld::PhysicsWorld(MemoryManager& memoryManager, PhysicsCommon& physicsC
|
|||
mNbPositionSolverIterations(mConfig.defaultPositionSolverNbIterations),
|
||||
mIsSleepingEnabled(mConfig.isSleepingEnabled), mRigidBodies(mMemoryManager.getPoolAllocator()),
|
||||
mIsGravityEnabled(true), mSleepLinearVelocity(mConfig.defaultSleepLinearVelocity),
|
||||
mSleepAngularVelocity(mConfig.defaultSleepAngularVelocity), mTimeBeforeSleep(mConfig.defaultTimeBeforeSleep), mCurrentJointId(0) {
|
||||
mSleepAngularVelocity(mConfig.defaultSleepAngularVelocity), mTimeBeforeSleep(mConfig.defaultTimeBeforeSleep) {
|
||||
|
||||
// Automatically generate a name for the world
|
||||
if (mName == "") {
|
||||
|
@ -375,7 +375,8 @@ void PhysicsWorld::update(decimal timeStep) {
|
|||
// Update the world inverse inertia tensors of rigid bodies
|
||||
void PhysicsWorld::updateBodiesInverseWorldInertiaTensors() {
|
||||
|
||||
for (uint i=0; i < mRigidBodyComponents.getNbEnabledComponents(); i++) {
|
||||
uint32 nbComponents = mRigidBodyComponents.getNbEnabledComponents();
|
||||
for (uint32 i=0; i < nbComponents; i++) {
|
||||
const Matrix3x3 orientation = mTransformComponents.getTransform(mRigidBodyComponents.mBodiesEntities[i]).getOrientation().getMatrix();
|
||||
|
||||
RigidBody::computeWorldInertiaTensorInverse(orientation, mRigidBodyComponents.mInverseInertiaTensorsLocal[i], mRigidBodyComponents.mInverseInertiaTensorsWorld[i]);
|
||||
|
@ -396,7 +397,7 @@ void PhysicsWorld::solveContactsAndConstraints(decimal timeStep) {
|
|||
mConstraintSolverSystem.initialize(timeStep);
|
||||
|
||||
// For each iteration of the velocity solver
|
||||
for (uint i=0; i<mNbVelocitySolverIterations; i++) {
|
||||
for (uint32 i=0; i<mNbVelocitySolverIterations; i++) {
|
||||
|
||||
mConstraintSolverSystem.solveVelocityConstraints();
|
||||
|
||||
|
@ -417,7 +418,7 @@ void PhysicsWorld::solvePositionCorrection() {
|
|||
// ---------- Solve the position error correction for the constraints ---------- //
|
||||
|
||||
// For each iteration of the position (error correction) solver
|
||||
for (uint i=0; i<mNbPositionSolverIterations; i++) {
|
||||
for (uint32 i=0; i<mNbPositionSolverIterations; i++) {
|
||||
|
||||
// Solve the position constraints
|
||||
mConstraintSolverSystem.solvePositionConstraints();
|
||||
|
@ -726,7 +727,7 @@ void PhysicsWorld::destroyJoint(Joint* joint) {
|
|||
/**
|
||||
* @param nbIterations Number of iterations for the velocity solver
|
||||
*/
|
||||
void PhysicsWorld::setNbIterationsVelocitySolver(uint nbIterations) {
|
||||
void PhysicsWorld::setNbIterationsVelocitySolver(uint32 nbIterations) {
|
||||
|
||||
mNbVelocitySolverIterations = nbIterations;
|
||||
|
||||
|
@ -766,7 +767,7 @@ void PhysicsWorld::createIslands() {
|
|||
|
||||
// Reset all the isAlreadyInIsland variables of bodies and joints
|
||||
const uint32 nbRigidBodyComponents = mRigidBodyComponents.getNbComponents();
|
||||
for (uint b=0; b < nbRigidBodyComponents; b++) {
|
||||
for (uint32 b=0; b < nbRigidBodyComponents; b++) {
|
||||
mRigidBodyComponents.mIsAlreadyInIsland[b] = false;
|
||||
}
|
||||
const uint32 nbJointsComponents = mJointsComponents.getNbComponents();
|
||||
|
@ -783,10 +784,10 @@ void PhysicsWorld::createIslands() {
|
|||
// Array of static bodies added to the current island (used to reset the isAlreadyInIsland variable of static bodies)
|
||||
Array<Entity> staticBodiesAddedToIsland(mMemoryManager.getSingleFrameAllocator(), 16);
|
||||
|
||||
uint nbTotalManifolds = 0;
|
||||
uint32 nbTotalManifolds = 0;
|
||||
|
||||
// For each rigid body component
|
||||
for (uint b=0; b < mRigidBodyComponents.getNbEnabledComponents(); b++) {
|
||||
for (uint32 b=0; b < mRigidBodyComponents.getNbEnabledComponents(); b++) {
|
||||
|
||||
// If the body has already been added to an island, we go to the next body
|
||||
if (mRigidBodyComponents.mIsAlreadyInIsland[b]) continue;
|
||||
|
@ -913,7 +914,7 @@ void PhysicsWorld::createIslands() {
|
|||
|
||||
// Clear the associated contacts pairs of rigid bodies
|
||||
const uint32 nbRigidBodyEnabledComponents = mRigidBodyComponents.getNbEnabledComponents();
|
||||
for (uint b=0; b < nbRigidBodyEnabledComponents; b++) {
|
||||
for (uint32 b=0; b < nbRigidBodyEnabledComponents; b++) {
|
||||
mRigidBodyComponents.mContactPairs[b].clear();
|
||||
}
|
||||
}
|
||||
|
@ -930,12 +931,12 @@ void PhysicsWorld::updateSleepingBodies(decimal timeStep) {
|
|||
|
||||
// For each island of the world
|
||||
const uint32 nbIslands = mIslands.getNbIslands();
|
||||
for (uint i=0; i < nbIslands; i++) {
|
||||
for (uint32 i=0; i < nbIslands; i++) {
|
||||
|
||||
decimal minSleepTime = DECIMAL_LARGEST;
|
||||
|
||||
// For each body of the island
|
||||
for (uint b=0; b < mIslands.nbBodiesInIsland[i]; b++) {
|
||||
for (uint32 b=0; b < mIslands.nbBodiesInIsland[i]; b++) {
|
||||
|
||||
const Entity bodyEntity = mIslands.bodyEntities[mIslands.startBodyEntitiesIndex[i] + b];
|
||||
const uint32 bodyIndex = mRigidBodyComponents.getEntityIndex(bodyEntity);
|
||||
|
@ -968,7 +969,7 @@ void PhysicsWorld::updateSleepingBodies(decimal timeStep) {
|
|||
if (minSleepTime >= mTimeBeforeSleep) {
|
||||
|
||||
// Put all the bodies of the island to sleep
|
||||
for (uint b=0; b < mIslands.nbBodiesInIsland[i]; b++) {
|
||||
for (uint32 b=0; b < mIslands.nbBodiesInIsland[i]; b++) {
|
||||
|
||||
const Entity bodyEntity = mIslands.bodyEntities[mIslands.startBodyEntitiesIndex[i] + b];
|
||||
RigidBody* body = mRigidBodyComponents.getRigidBody(bodyEntity);
|
||||
|
@ -1007,7 +1008,7 @@ void PhysicsWorld::enableSleeping(bool isSleepingEnabled) {
|
|||
/**
|
||||
* @param nbIterations Number of iterations for the position solver
|
||||
*/
|
||||
void PhysicsWorld::setNbIterationsPositionSolver(uint nbIterations) {
|
||||
void PhysicsWorld::setNbIterationsPositionSolver(uint32 nbIterations) {
|
||||
|
||||
mNbPositionSolverIterations = nbIterations;
|
||||
|
||||
|
@ -1086,7 +1087,7 @@ void PhysicsWorld::setIsGravityEnabled(bool isGravityEnabled) {
|
|||
* @param index Index of a CollisionBody in the world
|
||||
* @return Constant pointer to a given CollisionBody
|
||||
*/
|
||||
const CollisionBody* PhysicsWorld::getCollisionBody(uint index) const {
|
||||
const CollisionBody* PhysicsWorld::getCollisionBody(uint32 index) const {
|
||||
|
||||
if (index >= getNbCollisionBodies()) {
|
||||
|
||||
|
@ -1104,7 +1105,7 @@ const CollisionBody* PhysicsWorld::getCollisionBody(uint index) const {
|
|||
* @param index Index of a CollisionBody in the world
|
||||
* @return Pointer to a given CollisionBody
|
||||
*/
|
||||
CollisionBody* PhysicsWorld::getCollisionBody(uint index) {
|
||||
CollisionBody* PhysicsWorld::getCollisionBody(uint32 index) {
|
||||
|
||||
if (index >= getNbCollisionBodies()) {
|
||||
|
||||
|
@ -1122,7 +1123,7 @@ CollisionBody* PhysicsWorld::getCollisionBody(uint index) {
|
|||
* @param index Index of a RigidBody in the world
|
||||
* @return Constant pointer to a given RigidBody
|
||||
*/
|
||||
const RigidBody* PhysicsWorld::getRigidBody(uint index) const {
|
||||
const RigidBody* PhysicsWorld::getRigidBody(uint32 index) const {
|
||||
|
||||
if (index >= getNbRigidBodies()) {
|
||||
|
||||
|
@ -1140,7 +1141,7 @@ const RigidBody* PhysicsWorld::getRigidBody(uint index) const {
|
|||
* @param index Index of a RigidBody in the world
|
||||
* @return Pointer to a given RigidBody
|
||||
*/
|
||||
RigidBody* PhysicsWorld::getRigidBody(uint index) {
|
||||
RigidBody* PhysicsWorld::getRigidBody(uint32 index) {
|
||||
|
||||
if (index >= getNbRigidBodies()) {
|
||||
|
||||
|
|
|
@ -217,8 +217,8 @@ void CollisionDetectionSystem::updateOverlappingPairs(const Array<Pair<int32, in
|
|||
const Entity collider1Entity = mMapBroadPhaseIdToColliderEntity[nodePair.first];
|
||||
const Entity collider2Entity = mMapBroadPhaseIdToColliderEntity[nodePair.second];
|
||||
|
||||
const uint collider1Index = mCollidersComponents.getEntityIndex(collider1Entity);
|
||||
const uint collider2Index = mCollidersComponents.getEntityIndex(collider2Entity);
|
||||
const uint32 collider1Index = mCollidersComponents.getEntityIndex(collider1Entity);
|
||||
const uint32 collider2Index = mCollidersComponents.getEntityIndex(collider2Entity);
|
||||
|
||||
// Get the two bodies
|
||||
const Entity body1Entity = mCollidersComponents.mBodiesEntities[collider1Index];
|
||||
|
@ -317,8 +317,8 @@ void CollisionDetectionSystem::computeMiddlePhase(NarrowPhaseInput& narrowPhaseI
|
|||
const Entity collider1Entity = overlappingPair.collider1;
|
||||
const Entity collider2Entity = overlappingPair.collider2;
|
||||
|
||||
const uint collider1Index = mCollidersComponents.getEntityIndex(collider1Entity);
|
||||
const uint collider2Index = mCollidersComponents.getEntityIndex(collider2Entity);
|
||||
const uint32 collider1Index = mCollidersComponents.getEntityIndex(collider1Entity);
|
||||
const uint32 collider2Index = mCollidersComponents.getEntityIndex(collider2Entity);
|
||||
|
||||
CollisionShape* collisionShape1 = mCollidersComponents.mCollisionShapes[collider1Index];
|
||||
CollisionShape* collisionShape2 = mCollidersComponents.mCollisionShapes[collider2Index];
|
||||
|
@ -380,8 +380,8 @@ void CollisionDetectionSystem::computeMiddlePhaseCollisionSnapshot(Array<uint64>
|
|||
const Entity collider1Entity = mOverlappingPairs.mConvexPairs[pairIndex].collider1;
|
||||
const Entity collider2Entity = mOverlappingPairs.mConvexPairs[pairIndex].collider2;
|
||||
|
||||
const uint collider1Index = mCollidersComponents.getEntityIndex(collider1Entity);
|
||||
const uint collider2Index = mCollidersComponents.getEntityIndex(collider2Entity);
|
||||
const uint32 collider1Index = mCollidersComponents.getEntityIndex(collider1Entity);
|
||||
const uint32 collider2Index = mCollidersComponents.getEntityIndex(collider2Entity);
|
||||
|
||||
assert(mCollidersComponents.getBroadPhaseId(collider1Entity) != -1);
|
||||
assert(mCollidersComponents.getBroadPhaseId(collider2Entity) != -1);
|
||||
|
@ -402,8 +402,8 @@ void CollisionDetectionSystem::computeMiddlePhaseCollisionSnapshot(Array<uint64>
|
|||
}
|
||||
|
||||
// For each possible convex vs concave pair of bodies
|
||||
const uint nbConcavePairs = concavePairs.size();
|
||||
for (uint p=0; p < nbConcavePairs; p++) {
|
||||
const uint32 nbConcavePairs = concavePairs.size();
|
||||
for (uint32 p=0; p < nbConcavePairs; p++) {
|
||||
|
||||
const uint64 pairId = concavePairs[p];
|
||||
const uint64 pairIndex = mOverlappingPairs.mMapConcavePairIdToPairIndex[pairId];
|
||||
|
@ -424,8 +424,8 @@ void CollisionDetectionSystem::computeConvexVsConcaveMiddlePhase(OverlappingPair
|
|||
const Entity collider1 = overlappingPair.collider1;
|
||||
const Entity collider2 = overlappingPair.collider2;
|
||||
|
||||
const uint collider1Index = mCollidersComponents.getEntityIndex(collider1);
|
||||
const uint collider2Index = mCollidersComponents.getEntityIndex(collider2);
|
||||
const uint32 collider1Index = mCollidersComponents.getEntityIndex(collider1);
|
||||
const uint32 collider2Index = mCollidersComponents.getEntityIndex(collider2);
|
||||
|
||||
Transform& shape1LocalToWorldTransform = mCollidersComponents.mLocalToWorldTransforms[collider1Index];
|
||||
Transform& shape2LocalToWorldTransform = mCollidersComponents.mLocalToWorldTransforms[collider2Index];
|
||||
|
@ -722,7 +722,7 @@ void CollisionDetectionSystem::computeOverlapSnapshotContactPairs(NarrowPhaseInf
|
|||
RP3D_PROFILE("CollisionDetectionSystem::computeSnapshotContactPairs()", mProfiler);
|
||||
|
||||
// For each narrow phase info object
|
||||
for(uint i=0; i < narrowPhaseInfoBatch.getNbObjects(); i++) {
|
||||
for(uint32 i=0; i < narrowPhaseInfoBatch.getNbObjects(); i++) {
|
||||
|
||||
// If there is a collision
|
||||
if (narrowPhaseInfoBatch.narrowPhaseInfos[i].isColliding) {
|
||||
|
@ -833,7 +833,7 @@ void CollisionDetectionSystem::createContacts() {
|
|||
// Process the contact pairs in the order defined by the islands such that the contact manifolds and
|
||||
// contact points of a given island are packed together in the array of manifolds and contact points
|
||||
const uint32 nbContactPairsToProcess = mWorld->mProcessContactPairsOrderIslands.size();
|
||||
for (uint p=0; p < nbContactPairsToProcess; p++) {
|
||||
for (uint32 p=0; p < nbContactPairsToProcess; p++) {
|
||||
|
||||
uint32 contactPairIndex = mWorld->mProcessContactPairsOrderIslands[p];
|
||||
|
||||
|
@ -860,7 +860,7 @@ void CollisionDetectionSystem::createContacts() {
|
|||
assert(potentialManifold.potentialContactPointsIndices.size() > 0);
|
||||
|
||||
// For each contact point of the manifold
|
||||
for (uint c=0; c < nbContactPoints; c++) {
|
||||
for (uint32 c=0; c < nbContactPoints; c++) {
|
||||
|
||||
ContactPointInfo& potentialContactPoint = mPotentialContactPoints[potentialManifold.potentialContactPointsIndices[c]];
|
||||
|
||||
|
@ -1002,16 +1002,16 @@ void CollisionDetectionSystem::initContactsWithPreviousOnes() {
|
|||
// If we have found a corresponding contact pair in the previous frame
|
||||
if (itPrevContactPair != mPreviousMapPairIdToContactPairIndex.end()) {
|
||||
|
||||
const uint previousContactPairIndex = itPrevContactPair->second;
|
||||
const uint32 previousContactPairIndex = itPrevContactPair->second;
|
||||
ContactPair& previousContactPair = (*mPreviousContactPairs)[previousContactPairIndex];
|
||||
|
||||
// --------------------- Contact Manifolds --------------------- //
|
||||
|
||||
const uint contactManifoldsIndex = currentContactPair.contactManifoldsIndex;
|
||||
const uint nbContactManifolds = currentContactPair.nbContactManifolds;
|
||||
const uint32 contactManifoldsIndex = currentContactPair.contactManifoldsIndex;
|
||||
const uint32 nbContactManifolds = currentContactPair.nbContactManifolds;
|
||||
|
||||
// For each current contact manifold of the current contact pair
|
||||
for (uint m=contactManifoldsIndex; m < contactManifoldsIndex + nbContactManifolds; m++) {
|
||||
for (uint32 m=contactManifoldsIndex; m < contactManifoldsIndex + nbContactManifolds; m++) {
|
||||
|
||||
assert(m < mCurrentContactManifolds->size());
|
||||
ContactManifold& currentContactManifold = (*mCurrentContactManifolds)[m];
|
||||
|
@ -1020,9 +1020,9 @@ void CollisionDetectionSystem::initContactsWithPreviousOnes() {
|
|||
const Vector3& currentContactPointNormal = currentContactPoint.getNormal();
|
||||
|
||||
// Find a similar contact manifold among the contact manifolds from the previous frame (for warmstarting)
|
||||
const uint previousContactManifoldIndex = previousContactPair.contactManifoldsIndex;
|
||||
const uint previousNbContactManifolds = previousContactPair.nbContactManifolds;
|
||||
for (uint p=previousContactManifoldIndex; p < previousContactManifoldIndex + previousNbContactManifolds; p++) {
|
||||
const uint32 previousContactManifoldIndex = previousContactPair.contactManifoldsIndex;
|
||||
const uint32 previousNbContactManifolds = previousContactPair.nbContactManifolds;
|
||||
for (uint32 p=previousContactManifoldIndex; p < previousContactManifoldIndex + previousNbContactManifolds; p++) {
|
||||
|
||||
ContactManifold& previousContactManifold = (*mPreviousContactManifolds)[p];
|
||||
assert(previousContactManifold.nbContactPoints > 0);
|
||||
|
@ -1045,11 +1045,11 @@ void CollisionDetectionSystem::initContactsWithPreviousOnes() {
|
|||
|
||||
// --------------------- Contact Points --------------------- //
|
||||
|
||||
const uint contactPointsIndex = currentContactPair.contactPointsIndex;
|
||||
const uint nbTotalContactPoints = currentContactPair.nbToTalContactPoints;
|
||||
const uint32 contactPointsIndex = currentContactPair.contactPointsIndex;
|
||||
const uint32 nbTotalContactPoints = currentContactPair.nbToTalContactPoints;
|
||||
|
||||
// For each current contact point of the current contact pair
|
||||
for (uint c=contactPointsIndex; c < contactPointsIndex + nbTotalContactPoints; c++) {
|
||||
for (uint32 c=contactPointsIndex; c < contactPointsIndex + nbTotalContactPoints; c++) {
|
||||
|
||||
assert(c < mCurrentContactPoints->size());
|
||||
ContactPoint& currentContactPoint = (*mCurrentContactPoints)[c];
|
||||
|
@ -1057,9 +1057,9 @@ void CollisionDetectionSystem::initContactsWithPreviousOnes() {
|
|||
const Vector3& currentContactPointLocalShape1 = currentContactPoint.getLocalPointOnShape1();
|
||||
|
||||
// Find a similar contact point among the contact points from the previous frame (for warmstarting)
|
||||
const uint previousContactPointsIndex = previousContactPair.contactPointsIndex;
|
||||
const uint previousNbContactPoints = previousContactPair.nbToTalContactPoints;
|
||||
for (uint p=previousContactPointsIndex; p < previousContactPointsIndex + previousNbContactPoints; p++) {
|
||||
const uint32 previousContactPointsIndex = previousContactPair.contactPointsIndex;
|
||||
const uint32 previousNbContactPoints = previousContactPair.nbToTalContactPoints;
|
||||
for (uint32 p=previousContactPointsIndex; p < previousContactPointsIndex + previousNbContactPoints; p++) {
|
||||
|
||||
const ContactPoint& previousContactPoint = (*mPreviousContactPoints)[p];
|
||||
|
||||
|
@ -1124,12 +1124,12 @@ void CollisionDetectionSystem::processPotentialContacts(NarrowPhaseInfoBatch& na
|
|||
|
||||
RP3D_PROFILE("CollisionDetectionSystem::processPotentialContacts()", mProfiler);
|
||||
|
||||
const uint nbObjects = narrowPhaseInfoBatch.getNbObjects();
|
||||
const uint32 nbObjects = narrowPhaseInfoBatch.getNbObjects();
|
||||
|
||||
if (updateLastFrameInfo) {
|
||||
|
||||
// For each narrow phase info object
|
||||
for(uint i=0; i < nbObjects; i++) {
|
||||
for(uint32 i=0; i < nbObjects; i++) {
|
||||
|
||||
narrowPhaseInfoBatch.narrowPhaseInfos[i].lastFrameCollisionInfo->wasColliding = narrowPhaseInfoBatch.narrowPhaseInfos[i].isColliding;
|
||||
|
||||
|
@ -1139,7 +1139,7 @@ void CollisionDetectionSystem::processPotentialContacts(NarrowPhaseInfoBatch& na
|
|||
}
|
||||
|
||||
// For each narrow phase info object
|
||||
for(uint i=0; i < nbObjects; i++) {
|
||||
for(uint32 i=0; i < nbObjects; i++) {
|
||||
|
||||
// If the two colliders are colliding
|
||||
if (narrowPhaseInfoBatch.narrowPhaseInfos[i].isColliding) {
|
||||
|
@ -1183,7 +1183,7 @@ void CollisionDetectionSystem::processPotentialContacts(NarrowPhaseInfoBatch& na
|
|||
const uint32 contactPointIndexStart = static_cast<uint>(potentialContactPoints.size());
|
||||
|
||||
// Add the potential contacts
|
||||
for (uint j=0; j < narrowPhaseInfoBatch.narrowPhaseInfos[i].nbContactPoints; j++) {
|
||||
for (uint32 j=0; j < narrowPhaseInfoBatch.narrowPhaseInfos[i].nbContactPoints; j++) {
|
||||
|
||||
// Add the contact point to the manifold
|
||||
contactManifoldInfo.potentialContactPointsIndices.add(contactPointIndexStart + j);
|
||||
|
@ -1222,14 +1222,14 @@ void CollisionDetectionSystem::processPotentialContacts(NarrowPhaseInfoBatch& na
|
|||
|
||||
assert(it->first == pairId);
|
||||
|
||||
const uint pairContactIndex = it->second;
|
||||
const uint32 pairContactIndex = it->second;
|
||||
pairContact = &((*contactPairs)[pairContactIndex]);
|
||||
}
|
||||
|
||||
assert(pairContact != nullptr);
|
||||
|
||||
// Add the potential contacts
|
||||
for (uint j=0; j < narrowPhaseInfoBatch.narrowPhaseInfos[i].nbContactPoints; j++) {
|
||||
for (uint32 j=0; j < narrowPhaseInfoBatch.narrowPhaseInfos[i].nbContactPoints; j++) {
|
||||
|
||||
const ContactPointInfo& contactPoint = narrowPhaseInfoBatch.narrowPhaseInfos[i].contactPoints[j];
|
||||
|
||||
|
@ -1242,13 +1242,13 @@ void CollisionDetectionSystem::processPotentialContacts(NarrowPhaseInfoBatch& na
|
|||
|
||||
// For each contact manifold of the overlapping pair
|
||||
const uint32 nbPotentialManifolds = pairContact->potentialContactManifoldsIndices.size();
|
||||
for (uint m=0; m < nbPotentialManifolds; m++) {
|
||||
for (uint32 m=0; m < nbPotentialManifolds; m++) {
|
||||
|
||||
uint contactManifoldIndex = pairContact->potentialContactManifoldsIndices[m];
|
||||
uint32 contactManifoldIndex = pairContact->potentialContactManifoldsIndices[m];
|
||||
|
||||
// Get the first contact point of the current manifold
|
||||
assert(potentialContactManifolds[contactManifoldIndex].potentialContactPointsIndices.size() > 0);
|
||||
const uint manifoldContactPointIndex = potentialContactManifolds[contactManifoldIndex].potentialContactPointsIndices[0];
|
||||
const uint32 manifoldContactPointIndex = potentialContactManifolds[contactManifoldIndex].potentialContactPointsIndices[0];
|
||||
const ContactPointInfo& manifoldContactPoint = potentialContactPoints[manifoldContactPointIndex];
|
||||
|
||||
// If we have found a corresponding manifold for the new contact point
|
||||
|
@ -1396,7 +1396,7 @@ void CollisionDetectionSystem::reduceContactPoints(ContactManifoldInfo& manifold
|
|||
|
||||
int8 nbReducedPoints = 0;
|
||||
|
||||
uint pointsToKeepIndices[MAX_CONTACT_POINTS_IN_MANIFOLD];
|
||||
uint32 pointsToKeepIndices[MAX_CONTACT_POINTS_IN_MANIFOLD];
|
||||
for (int8 i=0; i<MAX_CONTACT_POINTS_IN_MANIFOLD; i++) {
|
||||
pointsToKeepIndices[i] = 0;
|
||||
}
|
||||
|
@ -1415,8 +1415,8 @@ void CollisionDetectionSystem::reduceContactPoints(ContactManifoldInfo& manifold
|
|||
// Compute a search direction
|
||||
const Vector3 searchDirection(1, 1, 1);
|
||||
decimal maxDotProduct = DECIMAL_SMALLEST;
|
||||
uint elementIndexToKeep = 0;
|
||||
for (uint i=0; i < candidatePointsIndices.size(); i++) {
|
||||
uint32 elementIndexToKeep = 0;
|
||||
for (uint32 i=0; i < candidatePointsIndices.size(); i++) {
|
||||
|
||||
const ContactPointInfo& element = potentialContactPoints[candidatePointsIndices[i]];
|
||||
decimal dotProduct = searchDirection.dot(element.localPoint1);
|
||||
|
@ -1436,7 +1436,7 @@ void CollisionDetectionSystem::reduceContactPoints(ContactManifoldInfo& manifold
|
|||
|
||||
decimal maxDistance = decimal(0.0);
|
||||
elementIndexToKeep = 0;
|
||||
for (uint i=0; i < candidatePointsIndices.size(); i++) {
|
||||
for (uint32 i=0; i < candidatePointsIndices.size(); i++) {
|
||||
|
||||
const ContactPointInfo& element = potentialContactPoints[candidatePointsIndices[i]];
|
||||
const ContactPointInfo& pointToKeep0 = potentialContactPoints[pointsToKeepIndices[0]];
|
||||
|
@ -1460,12 +1460,12 @@ void CollisionDetectionSystem::reduceContactPoints(ContactManifoldInfo& manifold
|
|||
// with first and second point.
|
||||
|
||||
// We compute the most positive or most negative triangle area (depending on winding)
|
||||
uint thirdPointMaxAreaIndex = 0;
|
||||
uint thirdPointMinAreaIndex = 0;
|
||||
uint32 thirdPointMaxAreaIndex = 0;
|
||||
uint32 thirdPointMinAreaIndex = 0;
|
||||
decimal minArea = decimal(0.0);
|
||||
decimal maxArea = decimal(0.0);
|
||||
bool isPreviousAreaPositive = true;
|
||||
for (uint i=0; i < candidatePointsIndices.size(); i++) {
|
||||
for (uint32 i=0; i < candidatePointsIndices.size(); i++) {
|
||||
|
||||
const ContactPointInfo& element = potentialContactPoints[candidatePointsIndices[i]];
|
||||
const ContactPointInfo& pointToKeep0 = potentialContactPoints[pointsToKeepIndices[0]];
|
||||
|
@ -1512,7 +1512,7 @@ void CollisionDetectionSystem::reduceContactPoints(ContactManifoldInfo& manifold
|
|||
decimal area;
|
||||
|
||||
// For each remaining candidate points
|
||||
for (uint i=0; i < candidatePointsIndices.size(); i++) {
|
||||
for (uint32 i=0; i < candidatePointsIndices.size(); i++) {
|
||||
|
||||
const ContactPointInfo& element = potentialContactPoints[candidatePointsIndices[i]];
|
||||
|
||||
|
@ -1521,10 +1521,10 @@ void CollisionDetectionSystem::reduceContactPoints(ContactManifoldInfo& manifold
|
|||
assert(candidatePointsIndices[i] != pointsToKeepIndices[2]);
|
||||
|
||||
// For each edge of the triangle made by the first three points
|
||||
for (uint j=0; j<3; j++) {
|
||||
for (uint32 j=0; j<3; j++) {
|
||||
|
||||
uint edgeVertex1Index = j;
|
||||
uint edgeVertex2Index = j < 2 ? j + 1 : 0;
|
||||
uint32 edgeVertex1Index = j;
|
||||
uint32 edgeVertex2Index = j < 2 ? j + 1 : 0;
|
||||
|
||||
const ContactPointInfo& pointToKeepEdgeV1 = potentialContactPoints[pointsToKeepIndices[edgeVertex1Index]];
|
||||
const ContactPointInfo& pointToKeepEdgeV2 = potentialContactPoints[pointsToKeepIndices[edgeVertex2Index]];
|
||||
|
@ -1831,8 +1831,8 @@ void CollisionDetectionSystem::filterOverlappingPairs(Entity body1Entity, Entity
|
|||
}
|
||||
|
||||
// For each concave pair
|
||||
const uint nbConcavePairs = mOverlappingPairs.mConcavePairs.size();
|
||||
for (uint i=0; i < nbConcavePairs; i++) {
|
||||
const uint32 nbConcavePairs = mOverlappingPairs.mConcavePairs.size();
|
||||
for (uint32 i=0; i < nbConcavePairs; i++) {
|
||||
|
||||
const Entity collider1Body = mCollidersComponents.getBody(mOverlappingPairs.mConcavePairs[i].collider1);
|
||||
const Entity collider2Body = mCollidersComponents.getBody(mOverlappingPairs.mConcavePairs[i].collider2);
|
||||
|
|
|
@ -91,8 +91,8 @@ void ContactSolverSystem::init(Array<ContactManifold>* contactManifolds, Array<C
|
|||
assert(mContactConstraints != nullptr);
|
||||
|
||||
// For each island of the world
|
||||
const uint nbIslands = mIslands.getNbIslands();
|
||||
for (uint i = 0; i < nbIslands; i++) {
|
||||
const uint32 nbIslands = mIslands.getNbIslands();
|
||||
for (uint32 i = 0; i < nbIslands; i++) {
|
||||
|
||||
if (mIslands.nbContactManifolds[i] > 0) {
|
||||
initializeForIsland(i);
|
||||
|
@ -111,7 +111,7 @@ void ContactSolverSystem::reset() {
|
|||
}
|
||||
|
||||
// Initialize the constraint solver for a given island
|
||||
void ContactSolverSystem::initializeForIsland(uint islandIndex) {
|
||||
void ContactSolverSystem::initializeForIsland(uint32 islandIndex) {
|
||||
|
||||
RP3D_PROFILE("ContactSolver::initializeForIsland()", mProfiler);
|
||||
|
||||
|
@ -119,23 +119,23 @@ void ContactSolverSystem::initializeForIsland(uint islandIndex) {
|
|||
assert(mIslands.nbContactManifolds[islandIndex] > 0);
|
||||
|
||||
// For each contact manifold of the island
|
||||
const uint contactManifoldsIndex = mIslands.contactManifoldsIndices[islandIndex];
|
||||
const uint nbContactManifolds = mIslands.nbContactManifolds[islandIndex];
|
||||
for (uint m=contactManifoldsIndex; m < contactManifoldsIndex + nbContactManifolds; m++) {
|
||||
const uint32 contactManifoldsIndex = mIslands.contactManifoldsIndices[islandIndex];
|
||||
const uint32 nbContactManifolds = mIslands.nbContactManifolds[islandIndex];
|
||||
for (uint32 m=contactManifoldsIndex; m < contactManifoldsIndex + nbContactManifolds; m++) {
|
||||
|
||||
ContactManifold& externalManifold = (*mAllContactManifolds)[m];
|
||||
|
||||
assert(externalManifold.nbContactPoints > 0);
|
||||
|
||||
const uint rigidBodyIndex1 = mRigidBodyComponents.getEntityIndex(externalManifold.bodyEntity1);
|
||||
const uint rigidBodyIndex2 = mRigidBodyComponents.getEntityIndex(externalManifold.bodyEntity2);
|
||||
const uint32 rigidBodyIndex1 = mRigidBodyComponents.getEntityIndex(externalManifold.bodyEntity1);
|
||||
const uint32 rigidBodyIndex2 = mRigidBodyComponents.getEntityIndex(externalManifold.bodyEntity2);
|
||||
|
||||
// Get the two bodies of the contact
|
||||
assert(!mBodyComponents.getIsEntityDisabled(externalManifold.bodyEntity1));
|
||||
assert(!mBodyComponents.getIsEntityDisabled(externalManifold.bodyEntity2));
|
||||
|
||||
const uint collider1Index = mColliderComponents.getEntityIndex(externalManifold.colliderEntity1);
|
||||
const uint collider2Index = mColliderComponents.getEntityIndex(externalManifold.colliderEntity2);
|
||||
const uint32 collider1Index = mColliderComponents.getEntityIndex(externalManifold.colliderEntity1);
|
||||
const uint32 collider2Index = mColliderComponents.getEntityIndex(externalManifold.colliderEntity2);
|
||||
|
||||
// Get the position of the two bodies
|
||||
const Vector3& x1 = mRigidBodyComponents.mCentersOfMassWorld[rigidBodyIndex1];
|
||||
|
@ -171,9 +171,9 @@ void ContactSolverSystem::initializeForIsland(uint islandIndex) {
|
|||
|
||||
// For each contact point of the contact manifold
|
||||
assert(externalManifold.nbContactPoints > 0);
|
||||
const uint contactPointsStartIndex = externalManifold.contactPointsIndex;
|
||||
const uint nbContactPoints = static_cast<uint>(externalManifold.nbContactPoints);
|
||||
for (uint c=contactPointsStartIndex; c < contactPointsStartIndex + nbContactPoints; c++) {
|
||||
const uint32 contactPointsStartIndex = externalManifold.contactPointsIndex;
|
||||
const uint32 nbContactPoints = static_cast<uint>(externalManifold.nbContactPoints);
|
||||
for (uint32 c=contactPointsStartIndex; c < contactPointsStartIndex + nbContactPoints; c++) {
|
||||
|
||||
ContactPoint& externalContact = (*mAllContactPoints)[c];
|
||||
|
||||
|
@ -330,10 +330,10 @@ void ContactSolverSystem::warmStart() {
|
|||
|
||||
RP3D_PROFILE("ContactSolver::warmStart()", mProfiler);
|
||||
|
||||
uint contactPointIndex = 0;
|
||||
uint32 contactPointIndex = 0;
|
||||
|
||||
// For each constraint
|
||||
for (uint c=0; c<mNbContactManifolds; c++) {
|
||||
for (uint32 c=0; c<mNbContactManifolds; c++) {
|
||||
|
||||
bool atLeastOneRestingContactPoint = false;
|
||||
|
||||
|
@ -485,12 +485,12 @@ void ContactSolverSystem::solve() {
|
|||
|
||||
decimal deltaLambda;
|
||||
decimal lambdaTemp;
|
||||
uint contactPointIndex = 0;
|
||||
uint32 contactPointIndex = 0;
|
||||
|
||||
const decimal beta = mIsSplitImpulseActive ? BETA_SPLIT_IMPULSE : BETA;
|
||||
|
||||
// For each contact manifold
|
||||
for (uint c=0; c<mNbContactManifolds; c++) {
|
||||
for (uint32 c=0; c<mNbContactManifolds; c++) {
|
||||
|
||||
decimal sumPenetrationImpulse = 0.0;
|
||||
|
||||
|
@ -767,10 +767,10 @@ void ContactSolverSystem::storeImpulses() {
|
|||
|
||||
RP3D_PROFILE("ContactSolver::storeImpulses()", mProfiler);
|
||||
|
||||
uint contactPointIndex = 0;
|
||||
uint32 contactPointIndex = 0;
|
||||
|
||||
// For each contact manifold
|
||||
for (uint c=0; c<mNbContactManifolds; c++) {
|
||||
for (uint32 c=0; c<mNbContactManifolds; c++) {
|
||||
|
||||
for (short int i=0; i<mContactConstraints[c].nbContacts; i++) {
|
||||
|
||||
|
|
|
@ -127,13 +127,13 @@ void DebugRenderer::drawSphere(const Vector3& position, decimal radius, uint32 c
|
|||
const decimal sectorStep = 2 * PI_RP3D / NB_SECTORS_SPHERE;
|
||||
const decimal stackStep = PI_RP3D / NB_STACKS_SPHERE;
|
||||
|
||||
for (uint i = 0; i <= NB_STACKS_SPHERE; i++) {
|
||||
for (uint32 i = 0; i <= NB_STACKS_SPHERE; i++) {
|
||||
|
||||
const decimal stackAngle = PI_RP3D / 2 - i * stackStep;
|
||||
const decimal radiusCosStackAngle = radius * std::cos(stackAngle);
|
||||
const decimal z = radius * std::sin(stackAngle);
|
||||
|
||||
for (uint j = 0; j <= NB_SECTORS_SPHERE; j++) {
|
||||
for (uint32 j = 0; j <= NB_SECTORS_SPHERE; j++) {
|
||||
|
||||
const decimal sectorAngle = j * sectorStep;
|
||||
const decimal x = radiusCosStackAngle * std::cos(sectorAngle);
|
||||
|
@ -144,12 +144,12 @@ void DebugRenderer::drawSphere(const Vector3& position, decimal radius, uint32 c
|
|||
}
|
||||
|
||||
// Faces
|
||||
for (uint i = 0; i < NB_STACKS_SPHERE; i++) {
|
||||
for (uint32 i = 0; i < NB_STACKS_SPHERE; i++) {
|
||||
|
||||
uint a1 = i * (NB_SECTORS_SPHERE + 1);
|
||||
uint a2 = a1 + NB_SECTORS_SPHERE + 1;
|
||||
uint32 a1 = i * (NB_SECTORS_SPHERE + 1);
|
||||
uint32 a2 = a1 + NB_SECTORS_SPHERE + 1;
|
||||
|
||||
for (uint j = 0; j < NB_SECTORS_SPHERE; j++, a1++, a2++) {
|
||||
for (uint32 j = 0; j < NB_SECTORS_SPHERE; j++, a1++, a2++) {
|
||||
|
||||
// 2 triangles per sector except for the first and last stacks
|
||||
|
||||
|
@ -174,23 +174,23 @@ void DebugRenderer::drawCapsule(const Transform& transform, decimal radius, deci
|
|||
const decimal halfHeight = 0.5 * height;
|
||||
|
||||
// Use an even number of stacks
|
||||
const uint nbStacks = NB_STACKS_SPHERE % 2 == 0 ? NB_STACKS_SPHERE : NB_STACKS_SPHERE - 1;
|
||||
const uint nbHalfStacks = nbStacks / 2;
|
||||
const uint32 nbStacks = NB_STACKS_SPHERE % 2 == 0 ? NB_STACKS_SPHERE : NB_STACKS_SPHERE - 1;
|
||||
const uint32 nbHalfStacks = nbStacks / 2;
|
||||
|
||||
// Vertices
|
||||
const decimal sectorStep = 2 * PI_RP3D / NB_SECTORS_SPHERE;
|
||||
const decimal stackStep = PI_RP3D / nbStacks;
|
||||
|
||||
uint vertexIndex = 0;
|
||||
uint32 vertexIndex = 0;
|
||||
|
||||
// Top cap sphere vertices
|
||||
for (uint i = 0; i <= nbHalfStacks; i++) {
|
||||
for (uint32 i = 0; i <= nbHalfStacks; i++) {
|
||||
|
||||
const decimal stackAngle = PI_RP3D / 2 - i * stackStep;
|
||||
const decimal radiusCosStackAngle = radius * std::cos(stackAngle);
|
||||
const decimal y = radius * std::sin(stackAngle);
|
||||
|
||||
for (uint j = 0; j <= NB_SECTORS_SPHERE; j++) {
|
||||
for (uint32 j = 0; j <= NB_SECTORS_SPHERE; j++) {
|
||||
|
||||
const decimal sectorAngle = j * sectorStep;
|
||||
const decimal x = radiusCosStackAngle * std::sin(sectorAngle);
|
||||
|
@ -204,13 +204,13 @@ void DebugRenderer::drawCapsule(const Transform& transform, decimal radius, deci
|
|||
}
|
||||
|
||||
// Bottom cap sphere vertices
|
||||
for (uint i = 0; i <= nbHalfStacks; i++) {
|
||||
for (uint32 i = 0; i <= nbHalfStacks; i++) {
|
||||
|
||||
const decimal stackAngle = PI_RP3D / 2 - (nbHalfStacks + i) * stackStep;
|
||||
const decimal radiusCosStackAngle = radius * std::cos(stackAngle);
|
||||
const decimal y = radius * std::sin(stackAngle);
|
||||
|
||||
for (uint j = 0; j <= NB_SECTORS_SPHERE; j++) {
|
||||
for (uint32 j = 0; j <= NB_SECTORS_SPHERE; j++) {
|
||||
|
||||
const decimal sectorAngle = j * sectorStep;
|
||||
const decimal x = radiusCosStackAngle * std::sin(sectorAngle);
|
||||
|
@ -224,12 +224,12 @@ void DebugRenderer::drawCapsule(const Transform& transform, decimal radius, deci
|
|||
}
|
||||
|
||||
// Faces of the top cap sphere
|
||||
for (uint i = 0; i < nbHalfStacks; i++) {
|
||||
for (uint32 i = 0; i < nbHalfStacks; i++) {
|
||||
|
||||
uint a1 = i * (NB_SECTORS_SPHERE + 1);
|
||||
uint a2 = a1 + NB_SECTORS_SPHERE + 1;
|
||||
uint32 a1 = i * (NB_SECTORS_SPHERE + 1);
|
||||
uint32 a2 = a1 + NB_SECTORS_SPHERE + 1;
|
||||
|
||||
for (uint j = 0; j < NB_SECTORS_SPHERE; j++, a1++, a2++) {
|
||||
for (uint32 j = 0; j < NB_SECTORS_SPHERE; j++, a1++, a2++) {
|
||||
|
||||
// 2 triangles per sector except for the first stack
|
||||
|
||||
|
@ -243,12 +243,12 @@ void DebugRenderer::drawCapsule(const Transform& transform, decimal radius, deci
|
|||
}
|
||||
|
||||
// Faces of the bottom cap sphere
|
||||
for (uint i = 0; i < nbHalfStacks; i++) {
|
||||
for (uint32 i = 0; i < nbHalfStacks; i++) {
|
||||
|
||||
uint a1 = (nbHalfStacks + 1) * (NB_SECTORS_SPHERE + 1) + i * (NB_SECTORS_SPHERE + 1);
|
||||
uint a2 = a1 + NB_SECTORS_SPHERE + 1;
|
||||
uint32 a1 = (nbHalfStacks + 1) * (NB_SECTORS_SPHERE + 1) + i * (NB_SECTORS_SPHERE + 1);
|
||||
uint32 a2 = a1 + NB_SECTORS_SPHERE + 1;
|
||||
|
||||
for (uint j = 0; j < NB_SECTORS_SPHERE; j++, a1++, a2++) {
|
||||
for (uint32 j = 0; j < NB_SECTORS_SPHERE; j++, a1++, a2++) {
|
||||
|
||||
// 2 triangles per sector except for the last stack
|
||||
|
||||
|
@ -262,9 +262,9 @@ void DebugRenderer::drawCapsule(const Transform& transform, decimal radius, deci
|
|||
}
|
||||
|
||||
// Faces of the cylinder between the two spheres
|
||||
uint a1 = nbHalfStacks * (NB_SECTORS_SPHERE + 1);
|
||||
uint a2 = a1 + NB_SECTORS_SPHERE + 1;
|
||||
for (uint i = 0; i < NB_SECTORS_SPHERE; i++, a1++, a2++) {
|
||||
uint32 a1 = nbHalfStacks * (NB_SECTORS_SPHERE + 1);
|
||||
uint32 a2 = a1 + NB_SECTORS_SPHERE + 1;
|
||||
for (uint32 i = 0; i < NB_SECTORS_SPHERE; i++, a1++, a2++) {
|
||||
|
||||
mTriangles.add(DebugTriangle(vertices[a1 + 1], vertices[a2], vertices[a2 + 1], color));
|
||||
mTriangles.add(DebugTriangle(vertices[a1], vertices[a2], vertices[a1 + 1], color));
|
||||
|
@ -284,9 +284,9 @@ void DebugRenderer::drawConvexMesh(const Transform& transform, const ConvexMeshS
|
|||
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];
|
||||
uint v3Index = face.faceVertices[v];
|
||||
uint32 v1Index = face.faceVertices[v - 2];
|
||||
uint32 v2Index = face.faceVertices[v - 1];
|
||||
uint32 v3Index = face.faceVertices[v];
|
||||
|
||||
Vector3 v1 = convexMesh->getVertexPosition(v1Index);
|
||||
Vector3 v2 = convexMesh->getVertexPosition(v2Index);
|
||||
|
@ -305,10 +305,10 @@ void DebugRenderer::drawConvexMesh(const Transform& transform, const ConvexMeshS
|
|||
void DebugRenderer::drawConcaveMeshShape(const Transform& transform, const ConcaveMeshShape* concaveMeshShape, uint32 color) {
|
||||
|
||||
// For each sub-part of the mesh
|
||||
for (uint p = 0; p < concaveMeshShape->getNbSubparts(); p++) {
|
||||
for (uint32 p = 0; p < concaveMeshShape->getNbSubparts(); p++) {
|
||||
|
||||
// For each triangle of the sub-part
|
||||
for (uint t = 0; t < concaveMeshShape->getNbTriangles(p); t++) {
|
||||
for (uint32 t = 0; t < concaveMeshShape->getNbTriangles(p); t++) {
|
||||
|
||||
Vector3 triangleVertices[3];
|
||||
concaveMeshShape->getTriangleVertices(p, t, triangleVertices);
|
||||
|
@ -401,11 +401,11 @@ void DebugRenderer::computeDebugRenderingPrimitives(const PhysicsWorld& world) {
|
|||
const bool drawColliderBroadphaseAABB = getIsDebugItemDisplayed(DebugItem::COLLIDER_BROADPHASE_AABB);
|
||||
const bool drawCollisionShape = getIsDebugItemDisplayed(DebugItem::COLLISION_SHAPE);
|
||||
|
||||
const uint nbCollisionBodies = world.getNbCollisionBodies();
|
||||
const uint nbRigidBodies = world.getNbRigidBodies();
|
||||
const uint32 nbCollisionBodies = world.getNbCollisionBodies();
|
||||
const uint32 nbRigidBodies = world.getNbRigidBodies();
|
||||
|
||||
// For each body of the world
|
||||
for (uint b = 0; b < nbCollisionBodies + nbRigidBodies; b++) {
|
||||
for (uint32 b = 0; b < nbCollisionBodies + nbRigidBodies; b++) {
|
||||
|
||||
// Get a body
|
||||
const CollisionBody* body = b < nbCollisionBodies ? world.getCollisionBody(b) : world.getRigidBody(b - nbCollisionBodies);
|
||||
|
@ -413,7 +413,7 @@ void DebugRenderer::computeDebugRenderingPrimitives(const PhysicsWorld& world) {
|
|||
if (body->isActive()) {
|
||||
|
||||
// For each collider of the body
|
||||
for (uint c = 0; c < body->getNbColliders(); c++) {
|
||||
for (uint32 c = 0; c < body->getNbColliders(); c++) {
|
||||
|
||||
// Get a collider
|
||||
const Collider* collider = body->getCollider(c);
|
||||
|
@ -449,14 +449,14 @@ void DebugRenderer::onContact(const CollisionCallback::CallbackData& callbackDat
|
|||
if (getIsDebugItemDisplayed(DebugItem::CONTACT_POINT) || getIsDebugItemDisplayed(DebugItem::CONTACT_NORMAL)) {
|
||||
|
||||
// For each contact pair
|
||||
for (uint p = 0; p < callbackData.getNbContactPairs(); p++) {
|
||||
for (uint32 p = 0; p < callbackData.getNbContactPairs(); p++) {
|
||||
|
||||
CollisionCallback::ContactPair contactPair = callbackData.getContactPair(p);
|
||||
|
||||
if (contactPair.getEventType() != CollisionCallback::ContactPair::EventType::ContactExit) {
|
||||
|
||||
// For each contact point of the contact pair
|
||||
for (uint c = 0; c < contactPair.getNbContactPoints(); c++) {
|
||||
for (uint32 c = 0; c < contactPair.getNbContactPoints(); c++) {
|
||||
|
||||
CollisionCallback::ContactPoint contactPoint = contactPair.getContactPoint(c);
|
||||
|
||||
|
|
|
@ -70,7 +70,7 @@ struct ContactPairData {
|
|||
|
||||
std::vector<CollisionPointData> contactPoints;
|
||||
|
||||
uint getNbContactPoints() const {
|
||||
uint32 getNbContactPoints() const {
|
||||
return contactPoints.size();
|
||||
}
|
||||
|
||||
|
@ -189,7 +189,7 @@ class WorldCollisionCallback : public CollisionCallback
|
|||
CollisionData collisionData;
|
||||
|
||||
// For each contact pair
|
||||
for (uint p=0; p < callbackData.getNbContactPairs(); p++) {
|
||||
for (uint32 p=0; p < callbackData.getNbContactPairs(); p++) {
|
||||
|
||||
ContactPairData contactPairData;
|
||||
ContactPair contactPair = callbackData.getContactPair(p);
|
||||
|
@ -198,7 +198,7 @@ class WorldCollisionCallback : public CollisionCallback
|
|||
collisionData.colliders = std::make_pair(contactPair.getCollider1(), contactPair.getCollider2());
|
||||
|
||||
// For each contact point
|
||||
for (uint c=0; c < contactPair.getNbContactPoints(); c++) {
|
||||
for (uint32 c=0; c < contactPair.getNbContactPoints(); c++) {
|
||||
|
||||
ContactPoint contactPoint = contactPair.getContactPoint(c);
|
||||
|
||||
|
@ -231,7 +231,7 @@ class WorldOverlapCallback : public OverlapCallback {
|
|||
virtual void onOverlap(CallbackData& callbackData) override {
|
||||
|
||||
// For each overlapping pair
|
||||
for (uint i=0; i < callbackData.getNbOverlappingPairs(); i++) {
|
||||
for (uint32 i=0; i < callbackData.getNbOverlappingPairs(); i++) {
|
||||
|
||||
OverlapPair overlapPair = callbackData.getOverlappingPair(i);
|
||||
mOverlapBodies.push_back(std::make_pair(overlapPair.getBody1(), overlapPair.getBody2()));
|
||||
|
@ -244,7 +244,7 @@ class WorldOverlapCallback : public OverlapCallback {
|
|||
|
||||
bool hasOverlapWithBody(CollisionBody* collisionBody) const {
|
||||
|
||||
for (uint i=0; i < mOverlapBodies.size(); i++) {
|
||||
for (uint32 i=0; i < mOverlapBodies.size(); i++) {
|
||||
|
||||
if (mOverlapBodies[i].first == collisionBody || mOverlapBodies[i].second == collisionBody) {
|
||||
return true;
|
||||
|
|
|
@ -71,17 +71,17 @@ class TestHalfEdgeStructure : public Test {
|
|||
cubeStructure.addVertex(7);
|
||||
|
||||
// Faces
|
||||
Array<uint> face0(mAllocator, 4);
|
||||
Array<uint32> face0(mAllocator, 4);
|
||||
face0.add(0); face0.add(1); face0.add(2); face0.add(3);
|
||||
Array<uint> face1(mAllocator, 4);
|
||||
Array<uint32> face1(mAllocator, 4);
|
||||
face1.add(1); face1.add(5); face1.add(6); face1.add(2);
|
||||
Array<uint> face2(mAllocator, 4);
|
||||
Array<uint32> face2(mAllocator, 4);
|
||||
face2.add(5); face2.add(4); face2.add(7); face2.add(6);
|
||||
Array<uint> face3(mAllocator, 4);
|
||||
Array<uint32> face3(mAllocator, 4);
|
||||
face3.add(4); face3.add(0); face3.add(3); face3.add(7);
|
||||
Array<uint> face4(mAllocator, 4);
|
||||
Array<uint32> face4(mAllocator, 4);
|
||||
face4.add(0); face4.add(4); face4.add(5); face4.add(1);
|
||||
Array<uint> face5(mAllocator, 4);
|
||||
Array<uint32> face5(mAllocator, 4);
|
||||
face5.add(2); face5.add(6); face5.add(7); face5.add(3);
|
||||
|
||||
cubeStructure.addFace(face0);
|
||||
|
@ -141,19 +141,19 @@ class TestHalfEdgeStructure : public Test {
|
|||
rp3d_test(cubeStructure.getHalfEdge(cubeStructure.getVertex(7).edgeIndex).vertexIndex == 7);
|
||||
|
||||
// Test faces
|
||||
for (uint f=0; f<6; f++) {
|
||||
for (uint32 f=0; f<6; f++) {
|
||||
rp3d_test(cubeStructure.getHalfEdge(cubeStructure.getFace(f).edgeIndex).faceIndex == f);
|
||||
}
|
||||
|
||||
// Test edges
|
||||
for (uint f=0; f<6; f++) {
|
||||
for (uint32 f=0; f<6; f++) {
|
||||
|
||||
|
||||
uint edgeIndex = cubeStructure.getFace(f).edgeIndex;
|
||||
const uint firstEdgeIndex = edgeIndex;
|
||||
uint32 edgeIndex = cubeStructure.getFace(f).edgeIndex;
|
||||
const uint32 firstEdgeIndex = edgeIndex;
|
||||
|
||||
// For each half-edge of the face
|
||||
for (uint e=0; e<4; e++) {
|
||||
for (uint32 e=0; e<4; e++) {
|
||||
|
||||
rp3d::HalfEdgeStructure::Edge edge = cubeStructure.getHalfEdge(edgeIndex);
|
||||
|
||||
|
@ -171,7 +171,7 @@ class TestHalfEdgeStructure : public Test {
|
|||
void testTetrahedron() {
|
||||
|
||||
// Create the half-edge structure for a tetrahedron
|
||||
std::vector<std::vector<uint>> faces;
|
||||
std::vector<std::vector<uint32>> faces;
|
||||
rp3d::HalfEdgeStructure tetrahedron(mAllocator, 4, 4, 12);
|
||||
|
||||
// Vertices
|
||||
|
@ -188,13 +188,13 @@ class TestHalfEdgeStructure : public Test {
|
|||
tetrahedron.addVertex(3);
|
||||
|
||||
// Faces
|
||||
Array<uint> face0(mAllocator, 3);
|
||||
Array<uint32> face0(mAllocator, 3);
|
||||
face0.add(0); face0.add(1); face0.add(2);
|
||||
Array<uint> face1(mAllocator, 3);
|
||||
Array<uint32> face1(mAllocator, 3);
|
||||
face1.add(0); face1.add(3); face1.add(1);
|
||||
Array<uint> face2(mAllocator, 3);
|
||||
Array<uint32> face2(mAllocator, 3);
|
||||
face2.add(1); face2.add(3); face2.add(2);
|
||||
Array<uint> face3(mAllocator, 3);
|
||||
Array<uint32> face3(mAllocator, 3);
|
||||
face3.add(0); face3.add(2); face3.add(3);
|
||||
|
||||
tetrahedron.addFace(face0);
|
||||
|
@ -232,18 +232,18 @@ class TestHalfEdgeStructure : public Test {
|
|||
rp3d_test(tetrahedron.getHalfEdge(tetrahedron.getVertex(3).edgeIndex).vertexIndex == 3);
|
||||
|
||||
// Test faces
|
||||
for (uint f=0; f<4; f++) {
|
||||
for (uint32 f=0; f<4; f++) {
|
||||
rp3d_test(tetrahedron.getHalfEdge(tetrahedron.getFace(f).edgeIndex).faceIndex == f);
|
||||
}
|
||||
|
||||
// Test edges
|
||||
for (uint f=0; f<4; f++) {
|
||||
for (uint32 f=0; f<4; f++) {
|
||||
|
||||
uint edgeIndex = tetrahedron.getFace(f).edgeIndex;
|
||||
const uint firstEdgeIndex = edgeIndex;
|
||||
uint32 edgeIndex = tetrahedron.getFace(f).edgeIndex;
|
||||
const uint32 firstEdgeIndex = edgeIndex;
|
||||
|
||||
// For each half-edge of the face
|
||||
for (uint e=0; e<3; e++) {
|
||||
for (uint32 e=0; e<3; e++) {
|
||||
|
||||
rp3d::HalfEdgeStructure::Edge edge = tetrahedron.getHalfEdge(edgeIndex);
|
||||
|
||||
|
|
|
@ -96,14 +96,14 @@ class TestArray : public Test {
|
|||
Array<int> array5(array3);
|
||||
rp3d_test(array5.capacity() == array3.capacity());
|
||||
rp3d_test(array5.size() == array3.size());
|
||||
for (uint i=0; i<array3.size(); i++) {
|
||||
for (uint32 i=0; i<array3.size(); i++) {
|
||||
rp3d_test(array5[i] == array3[i]);
|
||||
}
|
||||
|
||||
// ----- Test capacity grow ----- //
|
||||
Array<std::string> arra6(mAllocator, 20);
|
||||
rp3d_test(arra6.capacity() == 20);
|
||||
for (uint i=0; i<20; i++) {
|
||||
for (uint32 i=0; i<20; i++) {
|
||||
arra6.add("test");
|
||||
}
|
||||
rp3d_test(arra6.capacity() == 20);
|
||||
|
@ -127,11 +127,11 @@ class TestArray : public Test {
|
|||
const int arraySize = 15;
|
||||
int arrayTest[arraySize] = {3, 145, -182, 34, 12, 95, -1834, 4143, -111, -111, 4343, 234, 22983, -3432, 753};
|
||||
Array<int> array2(mAllocator);
|
||||
for (uint i=0; i<arraySize; i++) {
|
||||
for (uint32 i=0; i<arraySize; i++) {
|
||||
array2.add(arrayTest[i]);
|
||||
}
|
||||
rp3d_test(array2.size() == arraySize);
|
||||
for (uint i=0; i<arraySize; i++) {
|
||||
for (uint32 i=0; i<arraySize; i++) {
|
||||
rp3d_test(array2[i] == arrayTest[i]);
|
||||
}
|
||||
|
||||
|
|
|
@ -87,7 +87,7 @@ class TestDeque : public Test {
|
|||
rp3d_test(deque4.size() == deque2.size());
|
||||
Deque<int>::Iterator it3 = deque2.begin();
|
||||
Deque<int>::Iterator it5 = deque4.begin();
|
||||
for (uint i=0; i<deque2.size(); i++) {
|
||||
for (uint32 i=0; i<deque2.size(); i++) {
|
||||
rp3d_test((*it3) == (*it5));
|
||||
++it3;
|
||||
++it5;
|
||||
|
@ -95,7 +95,7 @@ class TestDeque : public Test {
|
|||
|
||||
// ----- Test capacity grow ----- //
|
||||
Deque<std::string> deque5(mAllocator);
|
||||
for (uint i=0; i<300; i++) {
|
||||
for (uint32 i=0; i<300; i++) {
|
||||
deque5.addBack("test");
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue
Block a user