Use List in HalfEdgeStructure with some changes in memory allocation

This commit is contained in:
Daniel Chappuis 2017-12-27 20:53:09 +01:00
parent f2ee00ca68
commit 8f126a75d6
42 changed files with 730 additions and 290 deletions

View File

@ -193,6 +193,8 @@ SET (REACTPHYSICS3D_SOURCES
"src/memory/SingleFrameAllocator.h"
"src/memory/SingleFrameAllocator.cpp"
"src/memory/DefaultAllocator.h"
"src/memory/MemoryManager.h"
"src/memory/MemoryManager.cpp"
"src/containers/Stack.h"
"src/containers/LinkedList.h"
"src/containers/List.h"

View File

@ -72,7 +72,7 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape,
// Create a new proxy collision shape to attach the collision shape to the body
ProxyShape* proxyShape = new (mWorld.mPoolAllocator.allocate(
sizeof(ProxyShape))) ProxyShape(this, collisionShape,
transform, decimal(1));
transform, decimal(1), mWorld.mPoolAllocator);
#ifdef IS_PROFILING_ACTIVE

View File

@ -226,7 +226,7 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape,
// Create a new proxy collision shape to attach the collision shape to the body
ProxyShape* proxyShape = new (mWorld.mPoolAllocator.allocate(
sizeof(ProxyShape))) ProxyShape(this, collisionShape,
transform, mass);
transform, mass, mWorld.mPoolAllocator);
#ifdef IS_PROFILING_ACTIVE

View File

@ -288,7 +288,14 @@ void CollisionDetection::computeNarrowPhase() {
lastCollisionFrameInfo->isValid = true;
}
NarrowPhaseInfo* narrowPhaseInfoToDelete = currentNarrowPhaseInfo;
currentNarrowPhaseInfo = currentNarrowPhaseInfo->next;
// Call the destructor
narrowPhaseInfoToDelete->~NarrowPhaseInfo();
// Release the allocated memory for the narrow phase info
mSingleFrameAllocator.release(narrowPhaseInfoToDelete, sizeof(NarrowPhaseInfo));
}
// Convert the potential contact into actual contacts

View File

@ -225,7 +225,6 @@ void ContactManifoldSet::removeManifold(ContactManifold* manifold) {
// Delete the contact manifold
manifold->~ContactManifold();
mMemoryAllocator.release(manifold, sizeof(ContactManifold));
mNbManifolds--;
}

View File

@ -96,8 +96,8 @@ void HalfEdgeStructure::init() {
mapEdgeToIndex.insert(std::make_pair(pairV1V2, edgeIndex + 1));
mapEdgeToIndex.insert(std::make_pair(pairV2V1, edgeIndex));
mEdges.push_back(itEdge->second);
mEdges.push_back(edge);
mEdges.add(itEdge->second);
mEdges.add(edge);
}
currentFaceEdges.push_back(pairV1V2);

View File

@ -50,14 +50,14 @@ class HalfEdgeStructure {
};
struct Face {
uint edgeIndex; // Index of an half-edge of the face
std::vector<uint> faceVertices; // Index of the vertices of the face
uint edgeIndex; // Index of an half-edge of the face
List<uint> faceVertices; // Index of the vertices of the face
/// Constructor
Face() {}
Face(Allocator& allocator) : faceVertices(allocator) {}
/// Constructor
Face(std::vector<uint> vertices) : faceVertices(vertices) {}
Face(List<uint> vertices) : faceVertices(vertices) {}
};
struct Vertex {
@ -70,19 +70,24 @@ class HalfEdgeStructure {
private:
/// Reference to a memory allocator
Allocator& mAllocator;
/// All the faces
std::vector<Face> mFaces;
List<Face> mFaces;
/// All the vertices
std::vector<Vertex> mVertices;
List<Vertex> mVertices;
/// All the half-edges
std::vector<Edge> mEdges;
List<Edge> mEdges;
public:
/// Constructor
HalfEdgeStructure() = default;
HalfEdgeStructure(Allocator& allocator, uint facesCapacity, uint verticesCapacity,
uint edgesCapacity) :mAllocator(allocator), mFaces(allocator, facesCapacity),
mVertices(allocator, verticesCapacity), mEdges(allocator, edgesCapacity) {}
/// Destructor
~HalfEdgeStructure() = default;
@ -94,7 +99,7 @@ class HalfEdgeStructure {
uint addVertex(uint vertexPointIndex);
/// Add a face
void addFace(std::vector<uint> faceVertices);
void addFace(List<uint> faceVertices);
/// Return the number of faces
uint getNbFaces() const;
@ -119,16 +124,16 @@ class HalfEdgeStructure {
// Add a vertex
inline uint HalfEdgeStructure::addVertex(uint vertexPointIndex) {
Vertex vertex(vertexPointIndex);
mVertices.push_back(vertex);
mVertices.add(vertex);
return mVertices.size() - 1;
}
// Add a face
inline void HalfEdgeStructure::addFace(std::vector<uint> faceVertices) {
inline void HalfEdgeStructure::addFace(List<uint> faceVertices) {
// Create a new face
Face face(faceVertices);
mFaces.push_back(face);
mFaces.add(face);
}
// Return the number of faces

View File

@ -34,7 +34,7 @@ void MiddlePhaseTriangleCallback::testTriangle(const Vector3* trianglePoints, co
// Create a triangle collision shape (the allocated memory for the TriangleShape will be released in the
// destructor of the corresponding NarrowPhaseInfo.
TriangleShape* triangleShape = new (mAllocator.allocate(sizeof(TriangleShape)))
TriangleShape(trianglePoints, verticesNormals, shapeId);
TriangleShape(trianglePoints, verticesNormals, shapeId, mAllocator);
#ifdef IS_PROFILING_ACTIVE

View File

@ -52,11 +52,13 @@ NarrowPhaseInfo::~NarrowPhaseInfo() {
// Release the memory of the TriangleShape (this memory was allocated in the
// MiddlePhaseTriangleCallback::testTriangle() method)
if (collisionShape1->getName() == CollisionShapeName::TRIANGLE) {
collisionShape1->~CollisionShape();
collisionShapeAllocator.release(collisionShape1, sizeof(TriangleShape));
}
if (collisionShape2->getName() == CollisionShapeName::TRIANGLE) {
collisionShapeAllocator.release(collisionShape2, sizeof(TriangleShape));
}
collisionShape2->~CollisionShape();
collisionShapeAllocator.release(collisionShape2, sizeof(TriangleShape));
}
}
// Add a new contact point

View File

@ -25,6 +25,7 @@
// Libraries
#include "PolyhedronMesh.h"
#include "memory/MemoryManager.h"
using namespace reactphysics3d;
@ -34,7 +35,11 @@ using namespace reactphysics3d;
* Create a polyhedron mesh given an array of polygons.
* @param polygonVertexArray Pointer to the array of polygons and their vertices
*/
PolyhedronMesh::PolyhedronMesh(PolygonVertexArray* polygonVertexArray) {
PolyhedronMesh::PolyhedronMesh(PolygonVertexArray* polygonVertexArray)
: mHalfEdgeStructure(MemoryManager::getDefaultAllocator(),
polygonVertexArray->getNbFaces(),
polygonVertexArray->getNbVertices(),
(polygonVertexArray->getNbFaces() + polygonVertexArray->getNbVertices() - 2) * 2) {
mPolygonVertexArray = polygonVertexArray;
@ -70,11 +75,11 @@ void PolyhedronMesh::createHalfEdgeStructure() {
// Get the polygon face
PolygonVertexArray::PolygonFace* face = mPolygonVertexArray->getPolygonFace(f);
std::vector<uint> faceVertices;
List<uint> faceVertices(MemoryManager::getDefaultAllocator(), face->nbVertices);
// For each vertex of the face
for (uint v=0; v < face->nbVertices; v++) {
faceVertices.push_back(mPolygonVertexArray->getVertexIndexInFace(f, v));
faceVertices.add(mPolygonVertexArray->getVertexIndexInFace(f, v));
}
assert(faceVertices.size() >= 3);

View File

@ -30,6 +30,7 @@
#include "mathematics/mathematics.h"
#include "HalfEdgeStructure.h"
#include "collision/PolygonVertexArray.h"
#include "memory/DefaultAllocator.h"
#include <vector>
namespace reactphysics3d {

View File

@ -35,9 +35,9 @@ using namespace reactphysics3d;
* @param transform Transformation from collision shape local-space to body local-space
* @param mass Mass of the collision shape (in kilograms)
*/
ProxyShape::ProxyShape(CollisionBody* body, CollisionShape* shape, const Transform& transform, decimal mass)
ProxyShape::ProxyShape(CollisionBody* body, CollisionShape* shape, const Transform& transform, decimal mass, Allocator& allocator)
:mBody(body), mCollisionShape(shape), mLocalToBodyTransform(transform), mMass(mass),
mNext(nullptr), mBroadPhaseID(-1), mCollisionCategoryBits(0x0001), mCollideWithMaskBits(0xFFFF) {
mNext(nullptr), mBroadPhaseID(-1), mCollisionCategoryBits(0x0001), mCollideWithMaskBits(0xFFFF), mAllocator(allocator) {
}
@ -76,7 +76,7 @@ bool ProxyShape::raycast(const Ray& ray, RaycastInfo& raycastInfo) {
worldToLocalTransform * ray.point2,
ray.maxFraction);
bool isHit = mCollisionShape->raycast(rayLocal, raycastInfo, this);
bool isHit = mCollisionShape->raycast(rayLocal, raycastInfo, this, mAllocator);
// Convert the raycast info into world-space
raycastInfo.worldPoint = localToWorldTransform * raycastInfo.worldPoint;

View File

@ -82,6 +82,9 @@ class ProxyShape {
/// proxy shape will collide with every collision categories by default.
unsigned short mCollideWithMaskBits;
/// Memory allocator
Allocator& mAllocator;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
@ -100,7 +103,7 @@ class ProxyShape {
/// Constructor
ProxyShape(CollisionBody* body, CollisionShape* shape,
const Transform& transform, decimal mass);
const Transform& transform, decimal mass, Allocator& allocator);
/// Destructor
virtual ~ProxyShape();

View File

@ -835,9 +835,8 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene
List<Vector3> planesPoints(mMemoryAllocator, nbIncidentFaceVertices); // Points on the clipping planes
// Get all the vertices of the incident face (in the reference local-space)
std::vector<uint>::const_iterator it;
for (it = incidentFace.faceVertices.begin(); it != incidentFace.faceVertices.end(); ++it) {
const Vector3 faceVertexIncidentSpace = incidentPolyhedron->getVertexPosition(*it);
for (uint i=0; i < incidentFace.faceVertices.size(); i++) {
const Vector3 faceVertexIncidentSpace = incidentPolyhedron->getVertexPosition(incidentFace.faceVertices[i]);
polygonVertices.add(incidentToReferenceTransform * faceVertexIncidentSpace);
}

View File

@ -27,6 +27,7 @@
#include "BoxShape.h"
#include "collision/ProxyShape.h"
#include "configuration.h"
#include "memory/MemoryManager.h"
#include <vector>
#include <cassert>
@ -37,7 +38,9 @@ using namespace reactphysics3d;
* @param extent The vector with the three extents of the box (in meters)
*/
BoxShape::BoxShape(const Vector3& extent)
: ConvexPolyhedronShape(CollisionShapeName::BOX), mExtent(extent) {
: ConvexPolyhedronShape(CollisionShapeName::BOX), mExtent(extent),
mHalfEdgeStructure(MemoryManager::getDefaultAllocator(), 6, 8, 24) {
assert(extent.x > decimal(0.0));
assert(extent.y > decimal(0.0));
assert(extent.z > decimal(0.0));
@ -52,19 +55,21 @@ BoxShape::BoxShape(const Vector3& extent)
mHalfEdgeStructure.addVertex(6);
mHalfEdgeStructure.addVertex(7);
DefaultAllocator& allocator = MemoryManager::getDefaultAllocator();
// Faces
std::vector<uint> face0;
face0.push_back(0); face0.push_back(1); face0.push_back(2); face0.push_back(3);
std::vector<uint> face1;
face1.push_back(1); face1.push_back(5); face1.push_back(6); face1.push_back(2);
std::vector<uint> face2;
face2.push_back(4); face2.push_back(7); face2.push_back(6); face2.push_back(5);
std::vector<uint> face3;
face3.push_back(4); face3.push_back(0); face3.push_back(3); face3.push_back(7);
std::vector<uint> face4;
face4.push_back(4); face4.push_back(5); face4.push_back(1); face4.push_back(0);
std::vector<uint> face5;
face5.push_back(2); face5.push_back(6); face5.push_back(7); face5.push_back(3);
List<uint> face0(allocator, 4);
face0.add(0); face0.add(1); face0.add(2); face0.add(3);
List<uint> face1(allocator, 4);
face1.add(1); face1.add(5); face1.add(6); face1.add(2);
List<uint> face2(allocator, 4);
face2.add(4); face2.add(7); face2.add(6); face2.add(5);
List<uint> face3(allocator, 4);
face3.add(4); face3.add(0); face3.add(3); face3.add(7);
List<uint> face4(allocator, 4);
face4.add(4); face4.add(5); face4.add(1); face4.add(0);
List<uint> face5(allocator, 4);
face5.add(2); face5.add(6); face5.add(7); face5.add(3);
mHalfEdgeStructure.addFace(face0);
mHalfEdgeStructure.addFace(face1);
@ -93,7 +98,7 @@ void BoxShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const
}
// Raycast method with feedback information
bool BoxShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
bool BoxShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const {
Vector3 rayDirection = ray.point2 - ray.point1;
decimal tMin = DECIMAL_SMALLEST;

View File

@ -31,7 +31,7 @@
#include "ConvexPolyhedronShape.h"
#include "body/CollisionBody.h"
#include "mathematics/mathematics.h"
#include "memory/DefaultAllocator.h"
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -64,7 +64,7 @@ class BoxShape : public ConvexPolyhedronShape {
virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override;
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const override;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const override;

View File

@ -85,7 +85,7 @@ bool CapsuleShape::testPointInside(const Vector3& localPoint, ProxyShape* proxyS
}
// Raycast method with feedback information
bool CapsuleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
bool CapsuleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const {
const Vector3 n = ray.point2 - ray.point1;

View File

@ -62,7 +62,7 @@ class CapsuleShape : public ConvexShape {
virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override;
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const override;
/// Raycasting method between a ray one of the two spheres end cap of the capsule
bool raycastWithSphereEndCap(const Vector3& point1, const Vector3& point2,

View File

@ -87,7 +87,7 @@ class CollisionShape {
virtual bool testPointInside(const Vector3& worldPoint, ProxyShape* proxyShape) const=0;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const=0;
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const=0;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const = 0;

View File

@ -111,12 +111,12 @@ void ConcaveMeshShape::testAllTriangles(TriangleCallback& callback, const AABB&
// Raycast method with feedback information
/// Note that only the first triangle hit by the ray in the mesh will be returned, even if
/// the ray hits many triangles.
bool ConcaveMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
bool ConcaveMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const {
PROFILE("ConcaveMeshShape::raycast()", mProfiler);
// Create the callback object that will compute ray casting against triangles
ConcaveMeshRaycastCallback raycastCallback(mDynamicAABBTree, *this, proxyShape, raycastInfo, ray);
ConcaveMeshRaycastCallback raycastCallback(mDynamicAABBTree, *this, proxyShape, raycastInfo, ray, allocator);
#ifdef IS_PROFILING_ACTIVE
@ -180,7 +180,7 @@ void ConcaveMeshRaycastCallback::raycastTriangles() {
mConcaveMeshShape.getTriangleVerticesNormals(data[0], data[1], verticesNormals);
// Create a triangle collision shape
TriangleShape triangleShape(trianglePoints, verticesNormals, mConcaveMeshShape.computeTriangleShapeId(data[0], data[1]));
TriangleShape triangleShape(trianglePoints, verticesNormals, mConcaveMeshShape.computeTriangleShapeId(data[0], data[1]), mAllocator);
triangleShape.setRaycastTestType(mConcaveMeshShape.getRaycastTestType());
#ifdef IS_PROFILING_ACTIVE
@ -192,7 +192,7 @@ void ConcaveMeshRaycastCallback::raycastTriangles() {
// Ray casting test against the collision shape
RaycastInfo raycastInfo;
bool isTriangleHit = triangleShape.raycast(mRay, raycastInfo, mProxyShape);
bool isTriangleHit = triangleShape.raycast(mRay, raycastInfo, mProxyShape, mAllocator);
// If the ray hit the collision shape
if (isTriangleHit && raycastInfo.hitFraction <= smallestHitFraction) {

View File

@ -77,6 +77,7 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback {
RaycastInfo& mRaycastInfo;
const Ray& mRay;
bool mIsHit;
Allocator& mAllocator;
#ifdef IS_PROFILING_ACTIVE
@ -89,9 +90,9 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback {
// Constructor
ConcaveMeshRaycastCallback(const DynamicAABBTree& dynamicAABBTree, const ConcaveMeshShape& concaveMeshShape,
ProxyShape* proxyShape, RaycastInfo& raycastInfo, const Ray& ray)
ProxyShape* proxyShape, RaycastInfo& raycastInfo, const Ray& ray, Allocator& allocator)
: mDynamicAABBTree(dynamicAABBTree), mConcaveMeshShape(concaveMeshShape), mProxyShape(proxyShape),
mRaycastInfo(raycastInfo), mRay(ray), mIsHit(false) {
mRaycastInfo(raycastInfo), mRay(ray), mIsHit(false), mAllocator(allocator) {
}
@ -141,7 +142,7 @@ class ConcaveMeshShape : public ConcaveShape {
// -------------------- Methods -------------------- //
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override;
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const override;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const override;

View File

@ -112,7 +112,7 @@ void ConvexMeshShape::recalculateBounds() {
}
// Raycast method with feedback information
bool ConvexMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
bool ConvexMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const {
return proxyShape->mBody->mWorld.mCollisionDetection.mNarrowPhaseGJKAlgorithm.raycast(
ray, proxyShape, raycastInfo);
}

View File

@ -77,7 +77,7 @@ class ConvexMeshShape : public ConvexPolyhedronShape {
virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override;
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const override;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const override;

View File

@ -212,14 +212,14 @@ void HeightFieldShape::computeMinMaxGridCoordinates(int* minCoords, int* maxCoor
// Raycast method with feedback information
/// Note that only the first triangle hit by the ray in the mesh will be returned, even if
/// the ray hits many triangles.
bool HeightFieldShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
bool HeightFieldShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const {
// TODO : Implement raycasting without using an AABB for the ray
// but using a dynamic AABB tree or octree instead
PROFILE("HeightFieldShape::raycast()", mProfiler);
TriangleOverlapCallback triangleCallback(ray, proxyShape, raycastInfo, *this);
TriangleOverlapCallback triangleCallback(ray, proxyShape, raycastInfo, *this, allocator);
#ifdef IS_PROFILING_ACTIVE
@ -266,7 +266,7 @@ Vector3 HeightFieldShape::getVertexAt(int x, int y) const {
void TriangleOverlapCallback::testTriangle(const Vector3* trianglePoints, const Vector3* verticesNormals, uint shapeId) {
// Create a triangle collision shape
TriangleShape triangleShape(trianglePoints, verticesNormals, shapeId);
TriangleShape triangleShape(trianglePoints, verticesNormals, shapeId, mAllocator);
triangleShape.setRaycastTestType(mHeightFieldShape.getRaycastTestType());
#ifdef IS_PROFILING_ACTIVE
@ -278,7 +278,7 @@ void TriangleOverlapCallback::testTriangle(const Vector3* trianglePoints, const
// Ray casting test against the collision shape
RaycastInfo raycastInfo;
bool isTriangleHit = triangleShape.raycast(mRay, raycastInfo, mProxyShape);
bool isTriangleHit = triangleShape.raycast(mRay, raycastInfo, mProxyShape, mAllocator);
// If the ray hit the collision shape
if (isTriangleHit && raycastInfo.hitFraction <= mSmallestHitFraction) {

View File

@ -49,6 +49,7 @@ class TriangleOverlapCallback : public TriangleCallback {
bool mIsHit;
decimal mSmallestHitFraction;
const HeightFieldShape& mHeightFieldShape;
Allocator& mAllocator;
#ifdef IS_PROFILING_ACTIVE
@ -61,9 +62,9 @@ class TriangleOverlapCallback : public TriangleCallback {
// Constructor
TriangleOverlapCallback(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& raycastInfo,
const HeightFieldShape& heightFieldShape)
const HeightFieldShape& heightFieldShape, Allocator& allocator)
: mRay(ray), mProxyShape(proxyShape), mRaycastInfo(raycastInfo),
mHeightFieldShape (heightFieldShape) {
mHeightFieldShape (heightFieldShape), mAllocator(allocator) {
mIsHit = false;
mSmallestHitFraction = mRay.maxFraction;
}
@ -143,7 +144,7 @@ class HeightFieldShape : public ConcaveShape {
// -------------------- Methods -------------------- //
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override;
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const override;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const override;

View File

@ -41,7 +41,7 @@ SphereShape::SphereShape(decimal radius)
}
// Raycast method with feedback information
bool SphereShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
bool SphereShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const {
const Vector3 m = ray.point1;
decimal c = m.dot(m) - mMargin * mMargin;

View File

@ -55,7 +55,7 @@ class SphereShape : public ConvexShape {
virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override;
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const override;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const override;

View File

@ -33,6 +33,7 @@
using namespace reactphysics3d;
// Constructor
/**
* Do not use this constructor. It is supposed to be used internally only.
@ -43,8 +44,9 @@ using namespace reactphysics3d;
* @param verticesNormals The three vertices normals for smooth mesh collision
* @param margin The collision margin (in meters) around the collision shape
*/
TriangleShape::TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint shapeId)
: ConvexPolyhedronShape(CollisionShapeName::TRIANGLE) {
TriangleShape::TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint shapeId,
Allocator& allocator)
: ConvexPolyhedronShape(CollisionShapeName::TRIANGLE), mFaces{HalfEdgeStructure::Face(allocator), HalfEdgeStructure::Face(allocator)} {
mPoints[0] = vertices[0];
mPoints[1] = vertices[1];
@ -60,9 +62,10 @@ TriangleShape::TriangleShape(const Vector3* vertices, const Vector3* verticesNor
// Faces
for (uint i=0; i<2; i++) {
mFaces[i].faceVertices.push_back(0);
mFaces[i].faceVertices.push_back(1);
mFaces[i].faceVertices.push_back(2);
mFaces[i].faceVertices.reserve(3);
mFaces[i].faceVertices.add(0);
mFaces[i].faceVertices.add(1);
mFaces[i].faceVertices.add(2);
mFaces[i].edgeIndex = i;
}
@ -208,7 +211,7 @@ Vector3 TriangleShape::computeSmoothLocalContactNormalForTriangle(const Vector3&
// Raycast method with feedback information
/// This method use the line vs triangle raycasting technique described in
/// Real-time Collision Detection by Christer Ericson.
bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const {
PROFILE("TriangleShape::raycast()", mProfiler);

View File

@ -60,6 +60,7 @@ class TriangleShape : public ConvexPolyhedronShape {
// -------------------- Attribute -------------------- //
/// Three points of the triangle
Vector3 mPoints[3];
@ -90,7 +91,8 @@ class TriangleShape : public ConvexPolyhedronShape {
virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override;
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape,
Allocator& allocator) const override;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const override;
@ -110,7 +112,8 @@ class TriangleShape : public ConvexPolyhedronShape {
// -------------------- Methods -------------------- //
/// Constructor
TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint shapeId);
TriangleShape(const Vector3* vertices, const Vector3* verticesNormals,
uint shapeId, Allocator& allocator);
/// Destructor
virtual ~TriangleShape() override = default;

View File

@ -44,59 +44,38 @@ class List {
// -------------------- Attributes -------------------- //
/// Pointer to the first element of the list
T* mElements;
/// Buffer for the list elements
void* mBuffer;
/// Number of elements in the list
uint mSize;
size_t mSize;
/// Number of allocated elements in the list
uint mCapacity;
size_t mCapacity;
/// Memory allocator
Allocator& mAllocator;
// -------------------- Methods -------------------- //
/// Allocate more memory for the elements of the list
void allocateMemory(uint nbElementsToAllocate) {
assert(nbElementsToAllocate > mCapacity);
// Allocate memory for the new array
void* newMemory = mAllocator.allocate(nbElementsToAllocate * sizeof(T));
if (mElements != nullptr) {
// Copy the elements to the new allocated memory location
std::memcpy(newMemory, static_cast<void*>(mElements), mSize * sizeof(T));
// Release the previously allocated memory
mAllocator.release(mElements, mCapacity * sizeof(T));
}
mElements = static_cast<T*>(newMemory);
mCapacity = nbElementsToAllocate;
}
public:
// -------------------- Methods -------------------- //
/// Constructor
List(Allocator& allocator, uint capacity = 0)
: mElements(nullptr), mSize(0), mCapacity(0), mAllocator(allocator) {
List(Allocator& allocator, size_t capacity = 0)
: mBuffer(nullptr), mSize(0), mCapacity(0), mAllocator(allocator) {
if (capacity > 0) {
// Allocate memory
allocateMemory(capacity);
reserve(capacity);
}
}
/// Copy constructor
List(const List<T>& list) : mElements(nullptr), mSize(0), mCapacity(0), mAllocator(list.mAllocator) {
List(const List<T>& list) : mBuffer(nullptr), mSize(0), mCapacity(0), mAllocator(list.mAllocator) {
// All all the elements of the list to the current one
addRange(list);
@ -112,22 +91,66 @@ class List {
clear();
// Release the memory allocated on the heap
mAllocator.release(static_cast<void*>(mElements), mCapacity * sizeof(T));
mAllocator.release(mBuffer, mCapacity * sizeof(T));
}
}
/// Allocate memory for a given number of elements
void reserve(size_t capacity) {
if (capacity <= mCapacity) return;
// Allocate memory for the new array
void* newMemory = mAllocator.allocate(capacity * sizeof(T));
if (mBuffer != nullptr) {
// Copy the elements to the new allocated memory location
std::memcpy(newMemory, mBuffer, mSize * sizeof(T));
// Release the previously allocated memory
mAllocator.release(mBuffer, mCapacity * sizeof(T));
}
mBuffer = newMemory;
assert(mBuffer != nullptr);
mCapacity = capacity;
}
/// Add an element into the list
void add(const T& element) {
// If we need to allocate more memory
if (mSize == mCapacity) {
allocateMemory(mCapacity == 0 ? 1 : mCapacity * 2);
reserve(mCapacity == 0 ? 1 : mCapacity * 2);
}
mElements[mSize] = element;
// Use the copy-constructor to construct the element
new (static_cast<char*>(mBuffer) + mSize * sizeof(T)) T(element);
mSize++;
}
/// Remove an element from the list at a given index
void remove(uint index) {
assert(index >= 0 && index < mSize);
// Call the destructor
(static_cast<T*>(mBuffer)[index]).~T();
mSize--;
if (index != mSize) {
// Move the elements to fill in the empty slot
char* dest = static_cast<char*>(mBuffer) + index * sizeof(T);
char* src = dest + sizeof(T);
std::memcpy(static_cast<void*>(dest), static_cast<void*>(src), (mSize - index) * sizeof(T));
}
}
/// Append another list to the current one
void addRange(const List<T>& list) {
@ -135,12 +158,13 @@ class List {
if (mSize + list.size() > mCapacity) {
// Allocate memory
allocateMemory(mSize + list.size());
reserve(mSize + list.size());
}
// Add the elements of the list to the current one
for(uint i=0; i<list.size(); i++) {
mElements[mSize] = list[i];
new (static_cast<char*>(mBuffer) + mSize * sizeof(T)) T(list[i]);
mSize++;
}
}
@ -150,27 +174,32 @@ class List {
// Call the destructor of each element
for (uint i=0; i < mSize; i++) {
mElements[i].~T();
(static_cast<T*>(mBuffer)[i]).~T();
}
mSize = 0;
}
/// Return the number of elments in the list
uint size() const {
size_t size() const {
return mSize;
}
/// Return the capacity of the list
size_t capacity() const {
return mCapacity;
}
/// Overloaded index operator
T& operator[](const uint index) {
assert(index >= 0 && index < mSize);
return mElements[index];
return (static_cast<T*>(mBuffer)[index]);
}
/// Overloaded const index operator
const T& operator[](const uint index) const {
assert(index >= 0 && index < mSize);
return mElements[index];
return (static_cast<T*>(mBuffer)[index]);
}
/// Overloaded assignment operator

View File

@ -187,4 +187,3 @@ AABB CollisionWorld::getWorldAABB(const ProxyShape* proxyShape) const {
return mCollisionDetection.getWorldAABB(proxyShape);
}

View File

@ -39,6 +39,7 @@
#include "collision/CollisionDetection.h"
#include "constraint/Joint.h"
#include "constraint/ContactPoint.h"
#include "memory/DefaultAllocator.h"
#include "memory/PoolAllocator.h"
#include "EventListener.h"

View File

@ -116,20 +116,16 @@ void OverlappingPair::addPotentialContactPoints(NarrowPhaseInfo* narrowPhaseInfo
// Clear all the potential contact manifolds
void OverlappingPair::clearPotentialContactManifolds() {
// Do we need to release memory
if (mTempMemoryAllocator.isReleaseNeeded()) {
ContactManifoldInfo* element = mPotentialContactManifolds;
while(element != nullptr) {
ContactManifoldInfo* element = mPotentialContactManifolds;
while(element != nullptr) {
// Remove the proxy collision shape
ContactManifoldInfo* elementToRemove = element;
element = element->getNext();
// Remove the proxy collision shape
ContactManifoldInfo* elementToRemove = element;
element = element->getNext();
// Delete the element
elementToRemove->~ContactManifoldInfo();
mTempMemoryAllocator.release(elementToRemove, sizeof(ContactManifoldInfo));
}
// Delete the element
elementToRemove->~ContactManifoldInfo();
mTempMemoryAllocator.release(elementToRemove, sizeof(ContactManifoldInfo));
}
mPotentialContactManifolds = nullptr;

View File

@ -0,0 +1,32 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2015 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
// Libraries
#include "MemoryManager.h"
using namespace reactphysics3d;
// Static variables
DefaultAllocator MemoryManager::mDefaultAllocator;

View File

@ -0,0 +1,74 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2016 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_MEMORY_MANAGER_H
#define REACTPHYSICS3D_MEMORY_MANAGER_H
// Libraries
#include "memory/DefaultAllocator.h"
/// Namespace ReactPhysics3D
namespace reactphysics3d {
// Class MemoryManager
/**
* The memory manager is used to store the different memory allocators that are used
* by the library.
*/
class MemoryManager {
private:
/// Default memory allocator
static DefaultAllocator mDefaultAllocator;
public:
/// Memory allocation types
enum class AllocationType {
Default, // Default memory allocator
Pool, // Memory pool allocator
Frame, // Single frame memory allocator
};
/// Constructor
MemoryManager();
/// Destructor
~MemoryManager();
/// Return the default memory allocator
static DefaultAllocator& getDefaultAllocator();
};
// Return the default memory allocator
inline DefaultAllocator& MemoryManager::getDefaultAllocator() {
return mDefaultAllocator;
}
}
#endif

View File

@ -126,7 +126,7 @@ void* PoolAllocator::allocate(size_t size) {
}
else { // If there is no more free memory units in the corresponding heap
// If we need to allocate more memory to containsthe blocks
// If we need to allocate more memory to contains the blocks
if (mNbCurrentMemoryBlocks == mNbAllocatedMemoryBlocks) {
// Allocate more memory to contain the blocks

View File

@ -94,7 +94,7 @@ class PoolAllocator : public Allocator {
/// Size of the memory units that each heap is responsible to allocate
static size_t mUnitSizes[NB_HEAPS];
/// Lookup table that mape size to allocate to the index of the
/// Lookup table that map the size to allocate to the index of the
/// corresponding heap we will use for the allocation.
static int mMapSizeToHeapIndex[MAX_UNIT_SIZE + 1];

499
test/tests/collision/TestCollisionWorld.h Normal file → Executable file
View File

@ -40,21 +40,108 @@ enum CollisionCategory {
CATEGORY_3 = 0x0004
};
// TODO : Add test for concave shape collision here
// Contact point collision data
struct CollisionPointData {
Vector3 localPointBody1;
Vector3 localPointBody2;
decimal penetrationDepth;
CollisionPointData(const Vector3& point1, const Vector3& point2, decimal penDepth) {
localPointBody1 = point1;
localPointBody2 = point2;
penetrationDepth = penDepth;
}
bool isContactPointSimilarTo(const Vector3& pointBody1, const Vector3& pointBody2, decimal penDepth, decimal epsilon = 0.001) {
return approxEqual(pointBody1, localPointBody1, epsilon) &&
approxEqual(pointBody2, localPointBody2, epsilon) &&
approxEqual(penetrationDepth, penDepth, epsilon);
}
};
// Contact manifold collision data
struct CollisionManifoldData {
std::vector<CollisionPointData> contactPoints;
int getNbContactPoints() const {
return contactPoints.size();
}
bool hasContactPointSimilarTo(const Vector3& localPointBody1, const Vector3& localPointBody2, decimal penetrationDepth, decimal epsilon = 0.001) {
std::vector<CollisionPointData>::iterator it;
for (it = contactPoints.begin(); it != contactPoints.end(); ++it) {
if (it->isContactPointSimilarTo(localPointBody1, localPointBody2, penetrationDepth)) {
return true;
}
}
return false;
}
};
// Collision data between two proxy shapes
struct CollisionData {
std::pair<const ProxyShape*, const ProxyShape*> proxyShapes;
std::pair<CollisionBody*, CollisionBody*> bodies;
std::vector<CollisionManifoldData> contactManifolds;
int getNbContactManifolds() const {
return contactManifolds.size();
}
int getTotalNbContactPoints() const {
int nbPoints = 0;
std::vector<CollisionManifoldData>::const_iterator it;
for (it = contactManifolds.begin(); it != contactManifolds.end(); ++it) {
nbPoints += it->getNbContactPoints();
}
return nbPoints;
}
bool hasContactPointSimilarTo(const Vector3& localPointBody1, const Vector3& localPointBody2, decimal penetrationDepth, decimal epsilon = 0.001) {
std::vector<CollisionManifoldData>::iterator it;
for (it = contactManifolds.begin(); it != contactManifolds.end(); ++it) {
if (it->hasContactPointSimilarTo(localPointBody1, localPointBody2, penetrationDepth)) {
return true;
}
}
return false;
}
};
// Class
class WorldCollisionCallback : public CollisionCallback
{
private:
std::vector<std::pair<const ProxyShape*, const ProxyShape*>> mCollisionData;
std::pair<const ProxyShape*, const ProxyShape*> getCollisionKeyPair(std::pair<const ProxyShape*, const ProxyShape*> pair) const {
if (pair.first > pair.second) {
return std::make_pair(pair.second, pair.first);
}
return pair;
}
public:
bool boxCollideWithSphere1;
bool sphere1CollideWithSphere2;
CollisionBody* boxBody;
CollisionBody* sphere1Body;
CollisionBody* sphere2Body;
CollisionBody* cylinderBody;
WorldCollisionCallback()
{
reset();
@ -62,30 +149,79 @@ class WorldCollisionCallback : public CollisionCallback
void reset()
{
boxCollideWithSphere1 = false;
sphere1CollideWithSphere2 = false;
mCollisionData.clear();
}
// This method will be called for contact
bool hasContacts() const {
return mCollisionData.size() > 0;
}
bool areProxyShapesColliding(const ProxyShape* proxyShape1, const ProxyShape* proxyShape2) {
return std::find(mCollisionData.begin(), mCollisionData.end(), getCollisionKeyPair(std::make_pair(proxyShape1, proxyShape2))) != mCollisionData.end();
}
// This method will be called for each contact
virtual void notifyContact(const CollisionCallbackInfo& collisionCallbackInfo) override {
if (isContactBetweenBodies(boxBody, sphere1Body, collisionCallbackInfo)) {
boxCollideWithSphere1 = true;
}
else if (isContactBetweenBodies(sphere1Body, sphere2Body, collisionCallbackInfo)) {
sphere1CollideWithSphere2 = true;
}
}
CollisionData collisionData;
collisionData.bodies = std::make_pair(collisionCallbackInfo.body1, collisionCallbackInfo.body2);
collisionData.proxyShapes = std::make_pair(collisionCallbackInfo.proxyShape1, collisionCallbackInfo.proxyShape2);
bool isContactBetweenBodies(const CollisionBody* body1, const CollisionBody* body2,
const CollisionCallbackInfo& collisionCallbackInfo) {
return (collisionCallbackInfo.body1->getID() == body1->getID() &&
collisionCallbackInfo.body2->getID() == body2->getID()) ||
(collisionCallbackInfo.body2->getID() == body1->getID() &&
collisionCallbackInfo.body1->getID() == body2->getID());
ContactManifoldListElement* element = collisionCallbackInfo.contactManifoldElements;
while (element != nullptr) {
ContactManifold* contactManifold = element->getContactManifold();
CollisionManifoldData collisionManifold;
ContactPoint* contactPoint = contactManifold->getContactPoints();
while (contactPoint != nullptr) {
CollisionPointData collisionPoint(contactPoint->getLocalPointOnShape1(), contactPoint->getLocalPointOnShape2(), contactPoint->getPenetrationDepth());
collisionManifold.contactPoints.push_back(collisionPoint);
contactPoint = contactPoint->getNext();
}
collisionData.contactManifolds.push_back(collisionManifold);
element = element->getNext();
}
}
};
/// Overlap callback
class WorldOverlapCallback : public OverlapCallback {
private:
CollisionBody* mOverlapBody;
public:
/// Destructor
virtual ~WorldOverlapCallback() {
reset();
}
/// This method will be called for each reported overlapping bodies
virtual void notifyOverlap(CollisionBody* collisionBody) override {
}
void reset() {
mOverlapBody = nullptr;
}
bool hasOverlap() const {
return mOverlapBody != nullptr;
}
CollisionBody* getOverlapBody() {
return mOverlapBody;
}
};
// Class TestCollisionWorld
/**
* Unit test for the CollisionWorld class.
@ -100,22 +236,29 @@ class TestCollisionWorld : public Test {
CollisionWorld* mWorld;
// Bodies
CollisionBody* mBoxBody;
CollisionBody* mSphere1Body;
CollisionBody* mSphere2Body;
CollisionBody* mBoxBody1;
CollisionBody* mBoxBody2;
CollisionBody* mSphereBody1;
CollisionBody* mSphereBody2;
// Collision shapes
BoxShape* mBoxShape;
SphereShape* mSphereShape;
BoxShape* mBoxShape1;
BoxShape* mBoxShape2;
SphereShape* mSphereShape1;
SphereShape* mSphereShape2;
// Proxy shapes
ProxyShape* mBoxProxyShape;
ProxyShape* mSphere1ProxyShape;
ProxyShape* mSphere2ProxyShape;
ProxyShape* mBoxProxyShape1;
ProxyShape* mBoxProxyShape2;
ProxyShape* mSphereProxyShape1;
ProxyShape* mSphereProxyShape2;
// Collision callback class
// Collision callback
WorldCollisionCallback mCollisionCallback;
// Overlap callback
WorldOverlapCallback mOverlapCallback;
public :
// ---------- Methods ---------- //
@ -123,147 +266,243 @@ class TestCollisionWorld : public Test {
/// Constructor
TestCollisionWorld(const std::string& name) : Test(name) {
// Create the world
// Create the collision world
mWorld = new CollisionWorld();
// Create the bodies
Transform boxTransform(Vector3(10, 0, 0), Quaternion::identity());
mBoxBody = mWorld->createCollisionBody(boxTransform);
mBoxShape = new BoxShape(Vector3(3, 3, 3));
mBoxProxyShape = mBoxBody->addCollisionShape(mBoxShape, Transform::identity());
// ---------- Boxes ---------- //
Transform boxTransform1(Vector3(-20, 20, 0), Quaternion::identity());
mBoxBody1 = mWorld->createCollisionBody(boxTransform1);
mBoxShape1 = new BoxShape(Vector3(3, 3, 3));
mBoxProxyShape1 = mBoxBody1->addCollisionShape(mBoxShape1, Transform::identity());
mSphereShape = new SphereShape(3.0);
Transform sphere1Transform(Vector3(10,5, 0), Quaternion::identity());
mSphere1Body = mWorld->createCollisionBody(sphere1Transform);
mSphere1ProxyShape = mSphere1Body->addCollisionShape(mSphereShape, Transform::identity());
Transform boxTransform2(Vector3(-10, 20, 0), Quaternion::identity());
mBoxBody2 = mWorld->createCollisionBody(boxTransform2);
mBoxShape2 = new BoxShape(Vector3(2, 2, 2));
mBoxProxyShape2 = mBoxBody2->addCollisionShape(mBoxShape1, Transform::identity());
Transform sphere2Transform(Vector3(30, 10, 10), Quaternion::identity());
mSphere2Body = mWorld->createCollisionBody(sphere2Transform);
mSphere2ProxyShape = mSphere2Body->addCollisionShape(mSphereShape, Transform::identity());
// ---------- Spheres ---------- //
mSphereShape1 = new SphereShape(3.0);
Transform sphereTransform1(Vector3(10, 20, 0), Quaternion::identity());
mSphereBody1 = mWorld->createCollisionBody(sphereTransform1);
mSphereProxyShape1 = mSphereBody1->addCollisionShape(mSphereShape1, Transform::identity());
// Assign collision categories to proxy shapes
mBoxProxyShape->setCollisionCategoryBits(CATEGORY_1);
mSphere1ProxyShape->setCollisionCategoryBits(CATEGORY_1);
mSphere2ProxyShape->setCollisionCategoryBits(CATEGORY_2);
mCollisionCallback.boxBody = mBoxBody;
mCollisionCallback.sphere1Body = mSphere1Body;
mCollisionCallback.sphere2Body = mSphere2Body;
mSphereShape2 = new SphereShape(5.0);
Transform sphereTransform2(Vector3(20, 20, 0), Quaternion::identity());
mSphereBody2 = mWorld->createCollisionBody(sphereTransform2);
mSphereProxyShape2 = mSphereBody2->addCollisionShape(mSphereShape2, Transform::identity());
}
/// Destructor
virtual ~TestCollisionWorld() {
delete mBoxShape;
delete mSphereShape;
delete mBoxShape1;
delete mBoxShape2;
delete mSphereShape1;
delete mSphereShape2;
delete mWorld;
}
/// Run the tests
void run() {
testCollisions();
testNoCollisions();
testNoOverlap();
testNoAABBOverlap();
testAABBOverlap();
testSphereVsSphereCollision();
testSphereVsBoxCollision();
testMultipleCollisions();
}
void testCollisions() {
void testNoCollisions() {
mCollisionCallback.reset();
mWorld->testCollision(&mCollisionCallback);
test(mCollisionCallback.boxCollideWithSphere1);
test(!mCollisionCallback.sphere1CollideWithSphere2);
// All the shapes of the world are not touching when they are created.
// Here we test that at the beginning, there is no collision at all.
test(mWorld->testAABBOverlap(mBoxBody, mSphere1Body));
test(!mWorld->testAABBOverlap(mSphere1Body, mSphere2Body));
// ---------- Global test ---------- //
test(mBoxProxyShape->testAABBOverlap(mSphere1ProxyShape->getWorldAABB()));
test(!mSphere1ProxyShape->testAABBOverlap(mSphere2ProxyShape->getWorldAABB()));
mCollisionCallback.reset();
mWorld->testCollision(&mCollisionCallback);
test(!mCollisionCallback.hasContacts());
mCollisionCallback.reset();
test(!mCollisionCallback.boxCollideWithSphere1);
test(!mCollisionCallback.sphere1CollideWithSphere2);
// ---------- Single body test ---------- //
mCollisionCallback.reset();
mWorld->testCollision(mBoxBody, mSphere1Body, &mCollisionCallback);
test(mCollisionCallback.boxCollideWithSphere1);
test(!mCollisionCallback.sphere1CollideWithSphere2);
mCollisionCallback.reset();
mWorld->testCollision(mBoxBody1, &mCollisionCallback);
test(!mCollisionCallback.hasContacts());
mCollisionCallback.reset();
test(!mCollisionCallback.boxCollideWithSphere1);
test(!mCollisionCallback.sphere1CollideWithSphere2);
mCollisionCallback.reset();
mWorld->testCollision(mBoxBody2, &mCollisionCallback);
test(!mCollisionCallback.hasContacts());
// Move sphere 1 to collide with sphere 2
mSphere1Body->setTransform(Transform(Vector3(30, 15, 10), Quaternion::identity()));
mCollisionCallback.reset();
mWorld->testCollision(mSphereBody1, &mCollisionCallback);
test(!mCollisionCallback.hasContacts());
mCollisionCallback.reset();
mWorld->testCollision(&mCollisionCallback);
test(!mCollisionCallback.boxCollideWithSphere1);
test(mCollisionCallback.sphere1CollideWithSphere2);
mCollisionCallback.reset();
mWorld->testCollision(mSphereBody2, &mCollisionCallback);
test(!mCollisionCallback.hasContacts());
mCollisionCallback.reset();
mWorld->testCollision(mBoxBody, mSphere1Body, &mCollisionCallback);
test(!mCollisionCallback.boxCollideWithSphere1);
test(!mCollisionCallback.sphere1CollideWithSphere2);
// Two bodies test
mCollisionCallback.reset();
test(!mCollisionCallback.boxCollideWithSphere1);
test(!mCollisionCallback.sphere1CollideWithSphere2);
mCollisionCallback.reset();
mWorld->testCollision(mBoxBody1, mBoxBody2, &mCollisionCallback);
test(!mCollisionCallback.hasContacts());
mCollisionCallback.reset();
mWorld->testCollision(mSphereBody1, mSphereBody2, &mCollisionCallback);
test(!mCollisionCallback.hasContacts());
mCollisionCallback.reset();
mWorld->testCollision(mBoxBody1, mSphereBody1, &mCollisionCallback);
test(!mCollisionCallback.hasContacts());
mCollisionCallback.reset();
mWorld->testCollision(mBoxBody1, mSphereBody2, &mCollisionCallback);
test(!mCollisionCallback.hasContacts());
mCollisionCallback.reset();
mWorld->testCollision(mBoxBody2, mSphereBody1, &mCollisionCallback);
test(!mCollisionCallback.hasContacts());
mCollisionCallback.reset();
mWorld->testCollision(mBoxBody2, mSphereBody2, &mCollisionCallback);
test(!mCollisionCallback.hasContacts());
}
void testNoOverlap() {
// All the shapes of the world are not touching when they are created.
// Here we test that at the beginning, there is no overlap at all.
// ---------- Single body test ---------- //
mOverlapCallback.reset();
mWorld->testOverlap(mBoxBody1, &mOverlapCallback);
test(!mOverlapCallback.hasOverlap());
mOverlapCallback.reset();
mWorld->testOverlap(mBoxBody2, &mOverlapCallback);
test(!mOverlapCallback.hasOverlap());
mOverlapCallback.reset();
mWorld->testOverlap(mSphereBody1, &mOverlapCallback);
test(!mOverlapCallback.hasOverlap());
mOverlapCallback.reset();
mWorld->testOverlap(mSphereBody2, &mOverlapCallback);
test(!mOverlapCallback.hasOverlap());
// Two bodies test
test(!mWorld->testOverlap(mBoxBody1, mBoxBody2));
test(!mWorld->testOverlap(mSphereBody1, mSphereBody2));
test(!mWorld->testOverlap(mBoxBody1, mSphereBody1));
test(!mWorld->testOverlap(mBoxBody1, mSphereBody2));
test(!mWorld->testOverlap(mBoxBody2, mSphereBody1));
test(!mWorld->testOverlap(mBoxBody2, mSphereBody2));
}
void testNoAABBOverlap() {
// All the shapes of the world are not touching when they are created.
// Here we test that at the beginning, there is no AABB overlap at all.
// Two bodies test
test(!mWorld->testAABBOverlap(mBoxBody1, mBoxBody2));
test(!mWorld->testAABBOverlap(mSphereBody1, mSphereBody2));
test(!mWorld->testAABBOverlap(mBoxBody1, mSphereBody1));
test(!mWorld->testAABBOverlap(mBoxBody1, mSphereBody2));
test(!mWorld->testAABBOverlap(mBoxBody2, mSphereBody1));
test(!mWorld->testAABBOverlap(mBoxBody2, mSphereBody2));
}
void testAABBOverlap() {
// TODO : Test the CollisionWorld::testAABBOverlap() method here
}
void testSphereVsSphereCollision() {
// Move sphere 1 to collide with sphere 2
mSphereBody1->setTransform(Transform(Vector3(30, 15, 10), Quaternion::identity()));
}
void testSphereVsBoxCollision() {
// Move sphere 1 to collide with box
mSphere1Body->setTransform(Transform(Vector3(10, 5, 0), Quaternion::identity()));
mSphereBody1->setTransform(Transform(Vector3(10, 5, 0), Quaternion::identity()));
// --------- Test collision with inactive bodies --------- //
mCollisionCallback.reset();
mBoxBody->setIsActive(false);
mSphere1Body->setIsActive(false);
mSphere2Body->setIsActive(false);
mBoxBody1->setIsActive(false);
mSphereBody1->setIsActive(false);
mSphereBody2->setIsActive(false);
mWorld->testCollision(&mCollisionCallback);
test(!mCollisionCallback.boxCollideWithSphere1);
test(!mCollisionCallback.sphere1CollideWithSphere2);
test(!mWorld->testAABBOverlap(mBoxBody, mSphere1Body));
test(!mWorld->testAABBOverlap(mSphere1Body, mSphere2Body));
test(!mBoxProxyShape->testAABBOverlap(mSphere1ProxyShape->getWorldAABB()));
test(!mSphere1ProxyShape->testAABBOverlap(mSphere2ProxyShape->getWorldAABB()));
mBoxBody->setIsActive(true);
mSphere1Body->setIsActive(true);
mSphere2Body->setIsActive(true);
mBoxBody1->setIsActive(true);
mSphereBody1->setIsActive(true);
mSphereBody2->setIsActive(true);
// --------- Test collision with collision filtering -------- //
mBoxProxyShape->setCollideWithMaskBits(CATEGORY_1 | CATEGORY_3);
mSphere1ProxyShape->setCollideWithMaskBits(CATEGORY_1 | CATEGORY_2);
mSphere2ProxyShape->setCollideWithMaskBits(CATEGORY_1);
//mBoxProxyShape->setCollideWithMaskBits(CATEGORY_1 | CATEGORY_3);
//mSphere1ProxyShape->setCollideWithMaskBits(CATEGORY_1 | CATEGORY_2);
//mSphere2ProxyShape->setCollideWithMaskBits(CATEGORY_1);
mCollisionCallback.reset();
mWorld->testCollision(&mCollisionCallback);
test(mCollisionCallback.boxCollideWithSphere1);
test(!mCollisionCallback.sphere1CollideWithSphere2);
//mCollisionCallback.reset();
//mWorld->testCollision(&mCollisionCallback);
//test(mCollisionCallback.boxCollideWithSphere1);
//test(!mCollisionCallback.sphere1CollideWithSphere2);
// Move sphere 1 to collide with sphere 2
mSphere1Body->setTransform(Transform(Vector3(30, 15, 10), Quaternion::identity()));
//// Move sphere 1 to collide with sphere 2
//mSphere1Body->setTransform(Transform(Vector3(30, 15, 10), Quaternion::identity()));
mCollisionCallback.reset();
mWorld->testCollision(&mCollisionCallback);
test(!mCollisionCallback.boxCollideWithSphere1);
test(mCollisionCallback.sphere1CollideWithSphere2);
//mCollisionCallback.reset();
//mWorld->testCollision(&mCollisionCallback);
//test(!mCollisionCallback.boxCollideWithSphere1);
//test(mCollisionCallback.sphere1CollideWithSphere2);
mBoxProxyShape->setCollideWithMaskBits(CATEGORY_2);
mSphere1ProxyShape->setCollideWithMaskBits(CATEGORY_2);
mSphere2ProxyShape->setCollideWithMaskBits(CATEGORY_3);
//mBoxProxyShape->setCollideWithMaskBits(CATEGORY_2);
//mSphere1ProxyShape->setCollideWithMaskBits(CATEGORY_2);
//mSphere2ProxyShape->setCollideWithMaskBits(CATEGORY_3);
mCollisionCallback.reset();
mWorld->testCollision(&mCollisionCallback);
test(!mCollisionCallback.boxCollideWithSphere1);
test(!mCollisionCallback.sphere1CollideWithSphere2);
//mCollisionCallback.reset();
//mWorld->testCollision(&mCollisionCallback);
//test(!mCollisionCallback.boxCollideWithSphere1);
//test(!mCollisionCallback.sphere1CollideWithSphere2);
// Move sphere 1 to collide with box
mSphere1Body->setTransform(Transform(Vector3(10, 5, 0), Quaternion::identity()));
//// Move sphere 1 to collide with box
//mSphere1Body->setTransform(Transform(Vector3(10, 5, 0), Quaternion::identity()));
mBoxProxyShape->setCollideWithMaskBits(0xFFFF);
mSphere1ProxyShape->setCollideWithMaskBits(0xFFFF);
mSphere2ProxyShape->setCollideWithMaskBits(0xFFFF);
//mBoxProxyShape->setCollideWithMaskBits(0xFFFF);
//mSphere1ProxyShape->setCollideWithMaskBits(0xFFFF);
//mSphere2ProxyShape->setCollideWithMaskBits(0xFFFF);
}
void testMultipleCollisions() {
// TODO : Test collisions without categories set
// TODO : Test colliisons with categories set
// Assign collision categories to proxy shapes
//mBoxProxyShape->setCollisionCategoryBits(CATEGORY_1);
//mSphere1ProxyShape->setCollisionCategoryBits(CATEGORY_1);
//mSphere2ProxyShape->setCollisionCategoryBits(CATEGORY_2);
}
};
}

29
test/tests/collision/TestDynamicAABBTree.h Normal file → Executable file
View File

@ -114,6 +114,12 @@ class TestDynamicAABBTree : public Test {
// Dynamic AABB Tree
DynamicAABBTree tree;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* profiler = new Profiler();
tree.setProfiler(profiler);
#endif
int object1Data = 56;
int object2Data = 23;
@ -152,6 +158,10 @@ class TestDynamicAABBTree : public Test {
test(*(int*)(tree.getNodeDataPointer(object2Id)) == object2Data);
test(*(int*)(tree.getNodeDataPointer(object3Id)) == object3Data);
test(*(int*)(tree.getNodeDataPointer(object4Id)) == object4Data);
#ifdef IS_PROFILING_ACTIVE
delete profiler;
#endif
}
void testOverlapping() {
@ -161,6 +171,12 @@ class TestDynamicAABBTree : public Test {
// Dynamic AABB Tree
DynamicAABBTree tree;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* profiler = new Profiler();
tree.setProfiler(profiler);
#endif
int object1Data = 56;
int object2Data = 23;
int object3Data = 13;
@ -342,6 +358,9 @@ class TestDynamicAABBTree : public Test {
test(!mOverlapCallback.isOverlapping(object3Id));
test(!mOverlapCallback.isOverlapping(object4Id));
#ifdef IS_PROFILING_ACTIVE
delete profiler;
#endif
}
void testRaycast() {
@ -351,6 +370,12 @@ class TestDynamicAABBTree : public Test {
// Dynamic AABB Tree
DynamicAABBTree tree;
#ifdef IS_PROFILING_ACTIVE
/// Pointer to the profiler
Profiler* profiler = new Profiler();
tree.setProfiler(profiler);
#endif
int object1Data = 56;
int object2Data = 23;
int object3Data = 13;
@ -513,6 +538,10 @@ class TestDynamicAABBTree : public Test {
test(!mRaycastCallback.isHit(object2Id));
test(mRaycastCallback.isHit(object3Id));
test(mRaycastCallback.isHit(object4Id));
#ifdef IS_PROFILING_ACTIVE
delete profiler;
#endif
}
};

View File

@ -19,6 +19,9 @@ class TestHalfEdgeStructure : public Test {
// ---------- Atributes ---------- //
/// Memory allocator
DefaultAllocator mAllocator;
public :
@ -43,7 +46,7 @@ class TestHalfEdgeStructure : public Test {
void testCube() {
// Create the half-edge structure for a cube
rp3d::HalfEdgeStructure cubeStructure;
rp3d::HalfEdgeStructure cubeStructure(mAllocator, 6, 8, 24);
rp3d::Vector3 vertices[8] = {
rp3d::Vector3(-0.5, -0.5, 0.5),
@ -67,18 +70,18 @@ class TestHalfEdgeStructure : public Test {
cubeStructure.addVertex(7);
// Faces
std::vector<uint> face0;
face0.push_back(0); face0.push_back(1); face0.push_back(2); face0.push_back(3);
std::vector<uint> face1;
face1.push_back(1); face1.push_back(5); face1.push_back(6); face1.push_back(2);
std::vector<uint> face2;
face2.push_back(5); face2.push_back(4); face2.push_back(7); face2.push_back(6);
std::vector<uint> face3;
face3.push_back(4); face3.push_back(0); face3.push_back(3); face3.push_back(7);
std::vector<uint> face4;
face4.push_back(0); face4.push_back(4); face4.push_back(5); face4.push_back(1);
std::vector<uint> face5;
face5.push_back(2); face5.push_back(6); face5.push_back(7); face5.push_back(3);
List<uint> face0(mAllocator, 4);
face0.add(0); face0.add(1); face0.add(2); face0.add(3);
List<uint> face1(mAllocator, 4);
face1.add(1); face1.add(5); face1.add(6); face1.add(2);
List<uint> face2(mAllocator, 4);
face2.add(5); face2.add(4); face2.add(7); face2.add(6);
List<uint> face3(mAllocator, 4);
face3.add(4); face3.add(0); face3.add(3); face3.add(7);
List<uint> face4(mAllocator, 4);
face4.add(0); face4.add(4); face4.add(5); face4.add(1);
List<uint> face5(mAllocator, 4);
face5.add(2); face5.add(6); face5.add(7); face5.add(3);
cubeStructure.addFace(face0);
cubeStructure.addFace(face1);
@ -168,7 +171,7 @@ class TestHalfEdgeStructure : public Test {
// Create the half-edge structure for a tetrahedron
std::vector<std::vector<uint>> faces;
rp3d::HalfEdgeStructure tetrahedron;
rp3d::HalfEdgeStructure tetrahedron(mAllocator, 4, 4, 12);
// Vertices
rp3d::Vector3 vertices[4] = {
@ -184,14 +187,14 @@ class TestHalfEdgeStructure : public Test {
tetrahedron.addVertex(3);
// Faces
std::vector<uint> face0;
face0.push_back(0); face0.push_back(1); face0.push_back(2);
std::vector<uint> face1;
face1.push_back(0); face1.push_back(3); face1.push_back(1);
std::vector<uint> face2;
face2.push_back(1); face2.push_back(3); face2.push_back(2);
std::vector<uint> face3;
face3.push_back(0); face3.push_back(2); face3.push_back(3);
List<uint> face0(mAllocator, 3);
face0.add(0); face0.add(1); face0.add(2);
List<uint> face1(mAllocator, 3);
face1.add(0); face1.add(3); face1.add(1);
List<uint> face2(mAllocator, 3);
face2.add(1); face2.add(3); face2.add(2);
List<uint> face3(mAllocator, 3);
face3.add(0); face3.add(2); face3.add(3);
tetrahedron.addFace(face0);
tetrahedron.addFace(face1);

View File

@ -99,6 +99,8 @@ class TestRaycast : public Test {
// Raycast callback class
WorldRaycastCallback mCallback;
DefaultAllocator mAllocator;
// Epsilon
decimal epsilon;
@ -203,7 +205,7 @@ class TestRaycast : public Test {
triangleVertices[1] = Vector3(105, 100, 0);
triangleVertices[2] = Vector3(100, 103, 0);
Vector3 triangleVerticesNormals[3] = {Vector3(0, 0, 1), Vector3(0, 0, 1), Vector3(0, 0, 1)};
mTriangleShape = new TriangleShape(triangleVertices, triangleVerticesNormals, 0);
mTriangleShape = new TriangleShape(triangleVertices, triangleVerticesNormals, 0, mAllocator);
mTriangleProxyShape = mTriangleBody->addCollisionShape(mTriangleShape, mShapeTransform);
mCapsuleShape = new CapsuleShape(2, 5);

View File

@ -176,13 +176,13 @@ class TestMathematicsFunctions : public Test {
segmentVertices.push_back(Vector3(-6, 3, 0));
segmentVertices.push_back(Vector3(8, 3, 0));
std::vector<Vector3> planesNormals;
std::vector<Vector3> planesPoints;
planesNormals.push_back(Vector3(-1, 0, 0));
planesPoints.push_back(Vector3(4, 0, 0));
List<Vector3> planesNormals(mAllocator, 2);
List<Vector3> planesPoints(mAllocator, 2);
planesNormals.add(Vector3(-1, 0, 0));
planesPoints.add(Vector3(4, 0, 0));
std::vector<Vector3> clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1],
planesPoints, planesNormals);
List<Vector3> clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1],
planesPoints, planesNormals, mAllocator);
test(clipSegmentVertices.size() == 2);
test(approxEqual(clipSegmentVertices[0].x, -6, 0.000001));
test(approxEqual(clipSegmentVertices[0].y, 3, 0.000001));
@ -195,7 +195,7 @@ class TestMathematicsFunctions : public Test {
segmentVertices.push_back(Vector3(8, 3, 0));
segmentVertices.push_back(Vector3(-6, 3, 0));
clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], planesPoints, planesNormals);
clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], planesPoints, planesNormals, mAllocator);
test(clipSegmentVertices.size() == 2);
test(approxEqual(clipSegmentVertices[0].x, 4, 0.000001));
test(approxEqual(clipSegmentVertices[0].y, 3, 0.000001));
@ -208,7 +208,7 @@ class TestMathematicsFunctions : public Test {
segmentVertices.push_back(Vector3(-6, 3, 0));
segmentVertices.push_back(Vector3(3, 3, 0));
clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], planesPoints, planesNormals);
clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], planesPoints, planesNormals, mAllocator);
test(clipSegmentVertices.size() == 2);
test(approxEqual(clipSegmentVertices[0].x, -6, 0.000001));
test(approxEqual(clipSegmentVertices[0].y, 3, 0.000001));
@ -221,7 +221,7 @@ class TestMathematicsFunctions : public Test {
segmentVertices.push_back(Vector3(5, 3, 0));
segmentVertices.push_back(Vector3(8, 3, 0));
clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], planesPoints, planesNormals);
clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], planesPoints, planesNormals, mAllocator);
test(clipSegmentVertices.size() == 0);
// Test clipPolygonWithPlanes()